QGroundControlQmlGlobal.h 14.1 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
#ifdef QT_DEBUG
#include "MockLink.h"
#endif

36 37
class QGCToolbox;

38
class QGroundControlQmlGlobal : public QGCTool
39 40 41 42
{
    Q_OBJECT

public:
43
    QGroundControlQmlGlobal(QGCApplication* app, QGCToolbox* toolbox);
44 45
    ~QGroundControlQmlGlobal();

46 47 48 49 50 51 52 53 54
    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)

55 56
    Q_PROPERTY(QString              appName             READ appName                CONSTANT)

Don Gagne's avatar
Don Gagne committed
57 58
    Q_PROPERTY(LinkManager*         linkManager         READ linkManager            CONSTANT)
    Q_PROPERTY(MultiVehicleManager* multiVehicleManager READ multiVehicleManager    CONSTANT)
Don Gagne's avatar
Don Gagne committed
59
    Q_PROPERTY(QGCMapEngineManager* mapEngineManager    READ mapEngineManager       CONSTANT)
Jimmy Johnson's avatar
Jimmy Johnson committed
60
    Q_PROPERTY(QGCPositionManager*  qgcPositionManger   READ qgcPositionManger      CONSTANT)
61
    Q_PROPERTY(MissionCommandTree*  missionCommandTree  READ missionCommandTree     CONSTANT)
62
    Q_PROPERTY(VideoManager*        videoManager        READ videoManager           CONSTANT)
Gus Grubba's avatar
Gus Grubba committed
63
    Q_PROPERTY(MAVLinkLogManager*   mavlinkLogManager   READ mavlinkLogManager      CONSTANT)
64
    Q_PROPERTY(QGCCorePlugin*       corePlugin          READ corePlugin             CONSTANT)
65
    Q_PROPERTY(SettingsManager*     settingsManager     READ settingsManager        CONSTANT)
66
    Q_PROPERTY(FactGroup*           gpsRtk              READ gpsRtkFactGroup        CONSTANT)
67
    Q_PROPERTY(AirspaceManager*     airspaceManager     READ airspaceManager        CONSTANT)
68
    Q_PROPERTY(bool                 airmapSupported     READ airmapSupported        CONSTANT)
69 70
    Q_PROPERTY(TaisyncManager*      taisyncManager      READ taisyncManager         CONSTANT)
    Q_PROPERTY(bool                 taisyncSupported    READ taisyncSupported       CONSTANT)
71

72
    Q_PROPERTY(int      supportedFirmwareCount          READ supportedFirmwareCount CONSTANT)
73 74
    Q_PROPERTY(bool     px4ProFirmwareSupported         READ px4ProFirmwareSupported CONSTANT)
    Q_PROPERTY(int      apmFirmwareSupported            READ apmFirmwareSupported CONSTANT)
Gus Grubba's avatar
Gus Grubba committed
75

76 77 78 79 80 81 82 83 84 85 86
    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 zOrderWimaAllWaypointIndicators        READ zOrderWimaAllWaypointIndicators        CONSTANT)
    Q_PROPERTY(qreal zOrderWimaCurrentWaypointIndicators    READ zOrderWimaCurrentWaypointIndicators    CONSTANT)
    Q_PROPERTY(qreal zOrderTrajectoryLines                  READ zOrderTrajectoryLines                  CONSTANT)
    Q_PROPERTY(qreal zOrderWaypointLines                    READ zOrderWaypointLines                    CONSTANT)
    Q_PROPERTY(qreal zOrderWimaAllWaypointLines             READ zOrderWimaAllWaypointLines             CONSTANT)
    Q_PROPERTY(qreal zOrderWimaCurrentWaypointLines         READ zOrderWimaCurrentWaypointLines         CONSTANT)
Gus Grubba's avatar
Gus Grubba committed
87

Gus Grubba's avatar
Gus Grubba committed
88
    //-------------------------------------------------------------------------
89
    // MavLink Protocol
Don Gagne's avatar
Don Gagne committed
90
    Q_PROPERTY(bool     isVersionCheckEnabled   READ isVersionCheckEnabled      WRITE setIsVersionCheckEnabled      NOTIFY isVersionCheckEnabledChanged)
91
    Q_PROPERTY(int      mavlinkSystemID         READ mavlinkSystemID            WRITE setMavlinkSystemID            NOTIFY mavlinkSystemIDChanged)
dogmaphobic's avatar
dogmaphobic committed
92

93 94
    Q_PROPERTY(QGeoCoordinate flightMapPosition     READ flightMapPosition      WRITE setFlightMapPosition          NOTIFY flightMapPositionChanged)
    Q_PROPERTY(double         flightMapZoom         READ flightMapZoom          WRITE setFlightMapZoom              NOTIFY flightMapZoomChanged)
95
    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
96

Don Gagne's avatar
Don Gagne committed
97 98 99 100
    Q_PROPERTY(QString  parameterFileExtension  READ parameterFileExtension CONSTANT)
    Q_PROPERTY(QString  missionFileExtension    READ missionFileExtension   CONSTANT)
    Q_PROPERTY(QString  telemetryFileExtension  READ telemetryFileExtension CONSTANT)

101 102
    /// Returns the string for distance units which has configued by user
    Q_PROPERTY(QString appSettingsDistanceUnitsString READ appSettingsDistanceUnitsString CONSTANT)
103
    Q_PROPERTY(QString appSettingsAreaUnitsString READ appSettingsAreaUnitsString CONSTANT)
104

105 106
    Q_PROPERTY(QString qgcVersion       READ qgcVersion         CONSTANT)
    Q_PROPERTY(bool    skipSetupPage    READ skipSetupPage      WRITE setSkipSetupPage NOTIFY skipSetupPageChanged)
107

108 109 110 111 112
    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);

113 114
    Q_INVOKABLE void    deleteAllSettingsNextBoot       () { _app->deleteAllSettingsNextBoot(); }
    Q_INVOKABLE void    clearDeleteAllSettingsNextBoot  () { _app->clearDeleteAllSettingsNextBoot(); }
115

116 117 118 119
    Q_INVOKABLE void    startPX4MockLink            (bool sendStatusText);
    Q_INVOKABLE void    startGenericMockLink        (bool sendStatusText);
    Q_INVOKABLE void    startAPMArduCopterMockLink  (bool sendStatusText);
    Q_INVOKABLE void    startAPMArduPlaneMockLink   (bool sendStatusText);
120
    Q_INVOKABLE void    startAPMArduSubMockLink     (bool sendStatusText);
Don Gagne's avatar
Don Gagne committed
121
    Q_INVOKABLE void    stopOneMockLink             (void);
122

123 124 125 126 127 128 129 130
    /// 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(); }

131 132 133 134 135 136 137 138
    /// 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(); }

139 140 141 142
    /// 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
143
    Q_INVOKABLE void setCategoryLoggingOn(const QString& category, bool enable) { QGCLoggingCategoryRegister::instance()->setCategoryLoggingOn(category, enable); }
144 145

    /// Returns true if logging is turned on for the specified category.
Don Gagne's avatar
Don Gagne committed
146
    Q_INVOKABLE bool categoryLoggingOn(const QString& category) { return QGCLoggingCategoryRegister::instance()->categoryLoggingOn(category); }
147 148 149 150

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

151 152
    Q_INVOKABLE bool linesIntersect(QPointF xLine1, QPointF yLine1, QPointF xLine2, QPointF yLine2);

153
    // Property accesors
Gus Grubba's avatar
Gus Grubba committed
154

155
    QString                 appName             ()  { return qgcApp()->applicationName(); }
156 157 158 159 160 161 162 163 164
    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; }
165
    FactGroup*              gpsRtkFactGroup     ()  { return _gpsRtkFactGroup; }
166
    AirspaceManager*        airspaceManager     ()  { return _airspaceManager; }
167 168
    static QGeoCoordinate   flightMapPosition   ()  { return _coord; }
    static double           flightMapZoom       ()  { return _zoom; }
169

170 171 172 173 174 175 176
    TaisyncManager*         taisyncManager      ()  { return _taisyncManager; }
#if defined(QGC_GST_TAISYNC_ENABLED)
    bool                    taisyncSupported    () { return true; }
#else
    bool                    taisyncSupported    () { return false; }
#endif

177 178 179 180 181 182 183 184 185 186 187
    qreal zOrderTopMost                         () { return 1000; }
    qreal zOrderWidgets                         () { return 200; }
    qreal zOrderMapItems                        () { return 150; }
    qreal zOrderWaypointIndicators              () { return 80; }
    qreal zOrderVehicles                        () { return 70; }
    qreal zOrderTrajectoryLines                 () { return 60; }
    qreal zOrderWaypointLines                   () { return 50; }
    qreal zOrderWimaCurrentWaypointIndicators   () { return 40; }
    qreal zOrderWimaAllWaypointIndicators       () { return 30; }
    qreal zOrderWimaCurrentWaypointLines        () { return 20; }
    qreal zOrderWimaAllWaypointLines            () { return 10; }
Gus Grubba's avatar
Gus Grubba committed
188

Don Gagne's avatar
Don Gagne committed
189
    bool    isVersionCheckEnabled   () { return _toolbox->mavlinkProtocol()->versionCheckEnabled(); }
190 191
    int     mavlinkSystemID         () { return _toolbox->mavlinkProtocol()->getSystemId(); }

192
    int     supportedFirmwareCount  ();
193 194
    bool    px4ProFirmwareSupported ();
    bool    apmFirmwareSupported    ();
195 196
    bool    skipSetupPage           () { return _skipSetupPage; }
    void    setSkipSetupPage        (bool skip);
Gus Grubba's avatar
Gus Grubba committed
197

Don Gagne's avatar
Don Gagne committed
198
    void    setIsVersionCheckEnabled    (bool enable);
199
    void    setMavlinkSystemID          (int  id);
200 201
    void    setFlightMapPosition        (QGeoCoordinate& coordinate);
    void    setFlightMapZoom            (double zoom);
dogmaphobic's avatar
dogmaphobic committed
202

203 204 205
    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
206

207 208
    QString qgcVersion(void) const { return qgcApp()->applicationVersion(); }

209 210 211 212 213
#if defined(QGC_AIRMAP_ENABLED)
    bool    airmapSupported() { return true; }
#else
    bool    airmapSupported() { return false; }
#endif
214

215 216 217
    // Overrides from QGCTool
    virtual void setToolbox(QGCToolbox* toolbox);

dogmaphobic's avatar
dogmaphobic committed
218 219
signals:
    void isMultiplexingEnabledChanged   (bool enabled);
Don Gagne's avatar
Don Gagne committed
220
    void isVersionCheckEnabledChanged   (bool enabled);
221
    void mavlinkSystemIDChanged         (int id);
222
    void flightMapPositionChanged       (QGeoCoordinate flightMapPosition);
223
    void flightMapZoomChanged           (double flightMapZoom);
224
    void skipSetupPageChanged           ();
dogmaphobic's avatar
dogmaphobic committed
225

226
private:
227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242
    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;

    bool                    _skipSetupPage          = false;
243 244 245 246 247

    static const char* _flightMapPositionSettingsGroup;
    static const char* _flightMapPositionLatitudeSettingsKey;
    static const char* _flightMapPositionLongitudeSettingsKey;
    static const char* _flightMapZoomSettingsKey;
248 249 250

    static QGeoCoordinate   _coord;
    static double           _zoom;
251 252 253
};

#endif