QGroundControlQmlGlobal.cc 6.65 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.
 *
 ****************************************************************************/
9

10 11 12 13 14

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

#include "QGroundControlQmlGlobal.h"
15 16

#include <QSettings>
Don Gagne's avatar
Don Gagne committed
17 18
#include <QLineF>
#include <QPointF>
19

Don Gagne's avatar
Don Gagne committed
20
static const char* kQmlGlobalKeyName = "QGCQml";
21

22 23 24 25 26
const char* QGroundControlQmlGlobal::_flightMapPositionSettingsGroup =          "FlightMapPosition";
const char* QGroundControlQmlGlobal::_flightMapPositionLatitudeSettingsKey =    "Latitude";
const char* QGroundControlQmlGlobal::_flightMapPositionLongitudeSettingsKey =   "Longitude";
const char* QGroundControlQmlGlobal::_flightMapZoomSettingsKey =                "FlightMapZoom";

27
QGeoCoordinate   QGroundControlQmlGlobal::_coord = QGeoCoordinate(0.0,0.0);
28
double           QGroundControlQmlGlobal::_zoom = 2;
29

30
QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app, QGCToolbox* toolbox)
31
    : QGCTool               (app, toolbox)
32
{
33
    // 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.
34
    setParent(nullptr);
35 36 37
    // Load last coordinates and zoom from config file
    QSettings settings;
    settings.beginGroup(_flightMapPositionSettingsGroup);
38 39 40
    _coord.setLatitude(settings.value(_flightMapPositionLatitudeSettingsKey,    _coord.latitude()).toDouble());
    _coord.setLongitude(settings.value(_flightMapPositionLongitudeSettingsKey,  _coord.longitude()).toDouble());
    _zoom = settings.value(_flightMapZoomSettingsKey, _zoom).toDouble();
41 42 43 44
}

QGroundControlQmlGlobal::~QGroundControlQmlGlobal()
{
45 46 47 48 49 50
    // Save last coordinates and zoom to config file
    QSettings settings;
    settings.beginGroup(_flightMapPositionSettingsGroup);
    settings.setValue(_flightMapPositionLatitudeSettingsKey, _coord.latitude());
    settings.setValue(_flightMapPositionLongitudeSettingsKey, _coord.longitude());
    settings.setValue(_flightMapZoomSettingsKey, _zoom);
51
}
52

53 54 55
void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox)
{
    QGCTool::setToolbox(toolbox);
56

dogmaphobic's avatar
dogmaphobic committed
57 58
    _linkManager            = toolbox->linkManager();
    _multiVehicleManager    = toolbox->multiVehicleManager();
Jimmy Johnson's avatar
Jimmy Johnson committed
59
    _mapEngineManager       = toolbox->mapEngineManager();
60 61
    _qgcPositionManager     = toolbox->qgcPositionManager();
    _missionCommandTree     = toolbox->missionCommandTree();
62
    _videoManager           = toolbox->videoManager();
Gus Grubba's avatar
Gus Grubba committed
63
    _mavlinkLogManager      = toolbox->mavlinkLogManager();
64
    _corePlugin             = toolbox->corePlugin();
Gus Grubba's avatar
Gus Grubba committed
65
    _firmwarePluginManager  = toolbox->firmwarePluginManager();
66
    _settingsManager        = toolbox->settingsManager();
67
    _gpsRtkFactGroup        = qgcApp()->gpsRtkFactGroup();
68
    _airspaceManager        = toolbox->airspaceManager();
69
#if defined(QGC_GST_TAISYNC_ENABLED)
70 71
    _taisyncManager         = toolbox->taisyncManager();
#endif
72 73
}

74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100
void QGroundControlQmlGlobal::saveGlobalSetting (const QString& key, const QString& value)
{
    QSettings settings;
    settings.beginGroup(kQmlGlobalKeyName);
    settings.setValue(key, value);
}

QString QGroundControlQmlGlobal::loadGlobalSetting (const QString& key, const QString& defaultValue)
{
    QSettings settings;
    settings.beginGroup(kQmlGlobalKeyName);
    return settings.value(key, defaultValue).toString();
}

void QGroundControlQmlGlobal::saveBoolGlobalSetting (const QString& key, bool value)
{
    QSettings settings;
    settings.beginGroup(kQmlGlobalKeyName);
    settings.setValue(key, value);
}

bool QGroundControlQmlGlobal::loadBoolGlobalSetting (const QString& key, bool defaultValue)
{
    QSettings settings;
    settings.beginGroup(kQmlGlobalKeyName);
    return settings.value(key, defaultValue).toBool();
}
101 102 103 104

void QGroundControlQmlGlobal::startPX4MockLink(bool sendStatusText)
{
#ifdef QT_DEBUG
105
    MockLink::startPX4MockLink(sendStatusText);
Don Gagne's avatar
Don Gagne committed
106 107
#else
    Q_UNUSED(sendStatusText);
108 109 110 111 112 113
#endif
}

void QGroundControlQmlGlobal::startGenericMockLink(bool sendStatusText)
{
#ifdef QT_DEBUG
114
    MockLink::startGenericMockLink(sendStatusText);
Don Gagne's avatar
Don Gagne committed
115 116
#else
    Q_UNUSED(sendStatusText);
117 118 119 120 121 122
#endif
}

void QGroundControlQmlGlobal::startAPMArduCopterMockLink(bool sendStatusText)
{
#ifdef QT_DEBUG
123
    MockLink::startAPMArduCopterMockLink(sendStatusText);
Don Gagne's avatar
Don Gagne committed
124 125
#else
    Q_UNUSED(sendStatusText);
126 127 128 129 130 131
#endif
}

void QGroundControlQmlGlobal::startAPMArduPlaneMockLink(bool sendStatusText)
{
#ifdef QT_DEBUG
132
    MockLink::startAPMArduPlaneMockLink(sendStatusText);
Don Gagne's avatar
Don Gagne committed
133 134
#else
    Q_UNUSED(sendStatusText);
135 136 137
#endif
}

138 139 140 141 142 143 144 145 146
void QGroundControlQmlGlobal::startAPMArduSubMockLink(bool sendStatusText)
{
#ifdef QT_DEBUG
    MockLink::startAPMArduSubMockLink(sendStatusText);
#else
    Q_UNUSED(sendStatusText);
#endif
}

Don Gagne's avatar
Don Gagne committed
147
void QGroundControlQmlGlobal::stopOneMockLink(void)
148 149 150 151
{
#ifdef QT_DEBUG
    LinkManager* linkManager = qgcApp()->toolbox()->linkManager();

152 153
    for (int i=0; i<linkManager->links().count(); i++) {
        LinkInterface* link = linkManager->links()[i];
154
        MockLink* mockLink = qobject_cast<MockLink*>(link);
Don Gagne's avatar
Don Gagne committed
155

156
        if (mockLink) {
Don Gagne's avatar
Don Gagne committed
157
            linkManager->disconnectLink(mockLink);
Don Gagne's avatar
Don Gagne committed
158
            return;
159 160 161 162
        }
    }
#endif
}
163

Don Gagne's avatar
Don Gagne committed
164 165 166 167 168 169
void QGroundControlQmlGlobal::setIsVersionCheckEnabled(bool enable)
{
    qgcApp()->toolbox()->mavlinkProtocol()->enableVersionCheck(enable);
    emit isVersionCheckEnabledChanged(enable);
}

170 171 172 173 174 175
void QGroundControlQmlGlobal::setMavlinkSystemID(int id)
{
    qgcApp()->toolbox()->mavlinkProtocol()->setSystemId(id);
    emit mavlinkSystemIDChanged(id);
}

Gus Grubba's avatar
Gus Grubba committed
176 177
int QGroundControlQmlGlobal::supportedFirmwareCount()
{
178
    return _firmwarePluginManager->supportedFirmwareTypes().count();
Gus Grubba's avatar
Gus Grubba committed
179 180 181
}


182 183 184 185 186 187 188
bool QGroundControlQmlGlobal::linesIntersect(QPointF line1A, QPointF line1B, QPointF line2A, QPointF line2B)
{
    QPointF intersectPoint;

    return QLineF(line1A, line1B).intersect(QLineF(line2A, line2B), &intersectPoint) == QLineF::BoundedIntersection &&
            intersectPoint != line1A && intersectPoint != line1B;
}
189 190 191 192 193 194 195 196

void QGroundControlQmlGlobal::setSkipSetupPage(bool skip)
{
    if(_skipSetupPage != skip) {
        _skipSetupPage = skip;
        emit skipSetupPageChanged();
    }
}
197 198 199 200

void QGroundControlQmlGlobal::setFlightMapPosition(QGeoCoordinate& coordinate)
{
    if (coordinate != flightMapPosition()) {
201 202
        _coord.setLatitude(coordinate.latitude());
        _coord.setLongitude(coordinate.longitude());
203 204 205 206 207 208 209 210

        emit flightMapPositionChanged(coordinate);
    }
}

void QGroundControlQmlGlobal::setFlightMapZoom(double zoom)
{
    if (zoom != flightMapZoom()) {
211
        _zoom = zoom;
212 213 214
        emit flightMapZoomChanged(zoom);
    }
}