QGroundControlQmlGlobal.cc 12.4 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
SettingsFact* QGroundControlQmlGlobal::_offlineEditingFirmwareTypeFact =        NULL;
FactMetaData* QGroundControlQmlGlobal::_offlineEditingFirmwareTypeMetaData =    NULL;
24 25 26 27
SettingsFact* QGroundControlQmlGlobal::_offlineEditingVehicleTypeFact =         NULL;
FactMetaData* QGroundControlQmlGlobal::_offlineEditingVehicleTypeMetaData =     NULL;
SettingsFact* QGroundControlQmlGlobal::_offlineEditingCruiseSpeedFact =         NULL;
SettingsFact* QGroundControlQmlGlobal::_offlineEditingHoverSpeedFact =          NULL;
28 29
SettingsFact* QGroundControlQmlGlobal::_distanceUnitsFact =                     NULL;
FactMetaData* QGroundControlQmlGlobal::_distanceUnitsMetaData =                 NULL;
30 31
SettingsFact* QGroundControlQmlGlobal::_areaUnitsFact =                         NULL;
FactMetaData* QGroundControlQmlGlobal::_areaUnitsMetaData =                     NULL;
32 33 34
SettingsFact* QGroundControlQmlGlobal::_speedUnitsFact =                        NULL;
FactMetaData* QGroundControlQmlGlobal::_speedUnitsMetaData =                    NULL;

35
const char* QGroundControlQmlGlobal::_virtualTabletJoystickKey  = "VirtualTabletJoystick";
36
const char* QGroundControlQmlGlobal::_baseFontPointSizeKey      = "BaseDeviceFontPointSize";
37

38 39 40 41 42 43
QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app)
    : QGCTool(app)
    , _flightMapSettings(NULL)
    , _homePositionManager(NULL)
    , _linkManager(NULL)
    , _multiVehicleManager(NULL)
dogmaphobic's avatar
dogmaphobic committed
44
    , _mapEngineManager(NULL)
45 46
    , _qgcPositionManager(NULL)
    , _missionCommandTree(NULL)
47
    , _virtualTabletJoystick(false)
48
    , _baseFontPointSize(0.0)
49
{
50
    QSettings settings;
51 52
    _virtualTabletJoystick  = settings.value(_virtualTabletJoystickKey, false).toBool();
    _baseFontPointSize      = settings.value(_baseFontPointSizeKey, 0.0).toDouble();
53

54 55
    // 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.
    setParent(NULL);
56 57 58 59 60
}

QGroundControlQmlGlobal::~QGroundControlQmlGlobal()
{

61
}
62

63 64 65 66

void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox)
{
    QGCTool::setToolbox(toolbox);
dogmaphobic's avatar
dogmaphobic committed
67 68 69 70
    _flightMapSettings      = toolbox->flightMapSettings();
    _homePositionManager    = toolbox->homePositionManager();
    _linkManager            = toolbox->linkManager();
    _multiVehicleManager    = toolbox->multiVehicleManager();
Jimmy Johnson's avatar
Jimmy Johnson committed
71
    _mapEngineManager       = toolbox->mapEngineManager();
72 73
    _qgcPositionManager     = toolbox->qgcPositionManager();
    _missionCommandTree     = toolbox->missionCommandTree();
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 101 102 103
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();
}
104 105 106 107

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

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

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

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

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

150 151 152 153 154
void QGroundControlQmlGlobal::stopAllMockLinks(void)
{
#ifdef QT_DEBUG
    LinkManager* linkManager = qgcApp()->toolbox()->linkManager();

Don Gagne's avatar
Don Gagne committed
155 156
    for (int i=0; i<linkManager->links()->count(); i++) {
        LinkInterface* link = linkManager->links()->value<LinkInterface*>(i);
157
        MockLink* mockLink = qobject_cast<MockLink*>(link);
Don Gagne's avatar
Don Gagne committed
158

159
        if (mockLink) {
Don Gagne's avatar
Don Gagne committed
160
            linkManager->disconnectLink(mockLink);
161 162 163 164
        }
    }
#endif
}
165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200

void QGroundControlQmlGlobal::setIsDarkStyle(bool dark)
{
    qgcApp()->setStyle(dark);
    emit isDarkStyleChanged(dark);
}

void QGroundControlQmlGlobal::setIsAudioMuted(bool muted)
{
    qgcApp()->toolbox()->audioOutput()->mute(muted);
    emit isAudioMutedChanged(muted);
}

void QGroundControlQmlGlobal::setIsSaveLogPrompt(bool prompt)
{
    qgcApp()->setPromptFlightDataSave(prompt);
    emit isSaveLogPromptChanged(prompt);
}

void QGroundControlQmlGlobal::setIsSaveLogPromptNotArmed(bool prompt)
{
    qgcApp()->setPromptFlightDataSaveNotArmed(prompt);
    emit isSaveLogPromptNotArmedChanged(prompt);
}

void QGroundControlQmlGlobal::setIsMultiplexingEnabled(bool enable)
{
    qgcApp()->toolbox()->mavlinkProtocol()->enableMultiplexing(enable);
    emit isMultiplexingEnabledChanged(enable);
}

void QGroundControlQmlGlobal::setIsVersionCheckEnabled(bool enable)
{
    qgcApp()->toolbox()->mavlinkProtocol()->enableVersionCheck(enable);
    emit isVersionCheckEnabledChanged(enable);
}
201

202 203 204 205 206 207
void QGroundControlQmlGlobal::setMavlinkSystemID(int id)
{
    qgcApp()->toolbox()->mavlinkProtocol()->setSystemId(id);
    emit mavlinkSystemIDChanged(id);
}

208 209 210 211 212 213 214 215 216
void QGroundControlQmlGlobal::setVirtualTabletJoystick(bool enabled)
{
    if (_virtualTabletJoystick != enabled) {
        QSettings settings;
        settings.setValue(_virtualTabletJoystickKey, enabled);
        _virtualTabletJoystick = enabled;
        emit virtualTabletJoystickChanged(enabled);
    }
}
217

218 219 220 221 222 223 224 225 226 227
void QGroundControlQmlGlobal::setBaseFontPointSize(qreal size)
{
    if (size >= 6.0 && size <= 48.0) {
        QSettings settings;
        settings.setValue(_baseFontPointSizeKey, size);
        _baseFontPointSize = size;
        emit baseFontPointSizeChanged(size);
    }
}

228 229 230 231 232 233 234 235 236
Fact* QGroundControlQmlGlobal::offlineEditingFirmwareType(void)
{
    if (!_offlineEditingFirmwareTypeFact) {
        QStringList     enumStrings;
        QVariantList    enumValues;

        _offlineEditingFirmwareTypeFact = new SettingsFact(QString(), "OfflineEditingFirmwareType", FactMetaData::valueTypeUint32, (uint32_t)MAV_AUTOPILOT_ARDUPILOTMEGA);
        _offlineEditingFirmwareTypeMetaData = new FactMetaData(FactMetaData::valueTypeUint32);

237
        enumStrings << tr("ArduPilot Firmware") << tr("PX4 Pro Firmware") << tr("Mavlink Generic Firmware");
238 239 240 241 242 243 244 245 246
        enumValues << QVariant::fromValue((uint32_t)MAV_AUTOPILOT_ARDUPILOTMEGA) << QVariant::fromValue((uint32_t)MAV_AUTOPILOT_PX4) << QVariant::fromValue((uint32_t)MAV_AUTOPILOT_GENERIC);

        _offlineEditingFirmwareTypeMetaData->setEnumInfo(enumStrings, enumValues);
        _offlineEditingFirmwareTypeFact->setMetaData(_offlineEditingFirmwareTypeMetaData);
    }

    return _offlineEditingFirmwareTypeFact;
}

247 248 249 250 251 252 253 254 255
Fact* QGroundControlQmlGlobal::offlineEditingVehicleType(void)
{
    if (!_offlineEditingVehicleTypeFact) {
        QStringList     enumStrings;
        QVariantList    enumValues;

        _offlineEditingVehicleTypeFact = new SettingsFact(QString(), "OfflineEditingVehicleType", FactMetaData::valueTypeUint32, (uint32_t)MAV_TYPE_FIXED_WING);
        _offlineEditingVehicleTypeMetaData = new FactMetaData(FactMetaData::valueTypeUint32);

256 257 258 259
        enumStrings << tr("Fixedwing") << tr("Multicopter") << tr("VTOL") << tr("Rover") << tr("Sub");
        enumValues << QVariant::fromValue((uint32_t)MAV_TYPE_FIXED_WING) << QVariant::fromValue((uint32_t)MAV_TYPE_QUADROTOR)
                   << QVariant::fromValue((uint32_t)MAV_TYPE_VTOL_DUOROTOR) << QVariant::fromValue((uint32_t)MAV_TYPE_GROUND_ROVER)
                   << QVariant::fromValue((uint32_t)MAV_TYPE_SUBMARINE);
260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283

        _offlineEditingVehicleTypeMetaData->setEnumInfo(enumStrings, enumValues);
        _offlineEditingVehicleTypeFact->setMetaData(_offlineEditingVehicleTypeMetaData);
    }

    return _offlineEditingVehicleTypeFact;
}

Fact* QGroundControlQmlGlobal::offlineEditingCruiseSpeed(void)
{
    if (!_offlineEditingCruiseSpeedFact) {
        _offlineEditingCruiseSpeedFact = new SettingsFact(QString(), "OfflineEditingCruiseSpeed", FactMetaData::valueTypeDouble, 16.0);
    }
    return _offlineEditingCruiseSpeedFact;
}

Fact* QGroundControlQmlGlobal::offlineEditingHoverSpeed(void)
{
    if (!_offlineEditingHoverSpeedFact) {
        _offlineEditingHoverSpeedFact = new SettingsFact(QString(), "OfflineEditingHoverSpeed", FactMetaData::valueTypeDouble, 4.0);
    }
    return _offlineEditingHoverSpeedFact;
}

284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303
Fact* QGroundControlQmlGlobal::distanceUnits(void)
{
    if (!_distanceUnitsFact) {
        QStringList     enumStrings;
        QVariantList    enumValues;

        _distanceUnitsFact = new SettingsFact(QString(), "DistanceUnits", FactMetaData::valueTypeUint32, DistanceUnitsMeters);
        _distanceUnitsMetaData = new FactMetaData(FactMetaData::valueTypeUint32);

        enumStrings << "Feet" << "Meters";
        enumValues << QVariant::fromValue((uint32_t)DistanceUnitsFeet) << QVariant::fromValue((uint32_t)DistanceUnitsMeters);

        _distanceUnitsMetaData->setEnumInfo(enumStrings, enumValues);
        _distanceUnitsFact->setMetaData(_distanceUnitsMetaData);
    }

    return _distanceUnitsFact;

}

304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323
Fact* QGroundControlQmlGlobal::areaUnits(void)
{
    if (!_areaUnitsFact) {
        QStringList     enumStrings;
        QVariantList    enumValues;

        _areaUnitsFact = new SettingsFact(QString(), "AreaUnits", FactMetaData::valueTypeUint32, AreaUnitsSquareMeters);
        _areaUnitsMetaData = new FactMetaData(FactMetaData::valueTypeUint32);

        enumStrings << "SquareFeet" << "SquareMeters" << "SquareKilometers" << "Hectares" << "Acres" << "SquareMiles";
        enumValues << QVariant::fromValue((uint32_t)AreaUnitsSquareFeet) << QVariant::fromValue((uint32_t)AreaUnitsSquareMeters) << QVariant::fromValue((uint32_t)AreaUnitsSquareKilometers) << QVariant::fromValue((uint32_t)AreaUnitsHectares) << QVariant::fromValue((uint32_t)AreaUnitsAcres) << QVariant::fromValue((uint32_t)AreaUnitsSquareMiles);

        _areaUnitsMetaData->setEnumInfo(enumStrings, enumValues);
        _areaUnitsFact->setMetaData(_areaUnitsMetaData);
    }

    return _areaUnitsFact;

}

324 325 326 327 328 329 330 331 332
Fact* QGroundControlQmlGlobal::speedUnits(void)
{
    if (!_speedUnitsFact) {
        QStringList     enumStrings;
        QVariantList    enumValues;

        _speedUnitsFact = new SettingsFact(QString(), "SpeedUnits", FactMetaData::valueTypeUint32, SpeedUnitsMetersPerSecond);
        _speedUnitsMetaData = new FactMetaData(FactMetaData::valueTypeUint32);

333
        enumStrings << "Feet/second" << "Meters/second" << "Miles/hour" << "Kilometers/hour" << "Knots";
334 335 336 337 338 339 340 341
        enumValues << QVariant::fromValue((uint32_t)SpeedUnitsFeetPerSecond) << QVariant::fromValue((uint32_t)SpeedUnitsMetersPerSecond) << QVariant::fromValue((uint32_t)SpeedUnitsMilesPerHour) << QVariant::fromValue((uint32_t)SpeedUnitsKilometersPerHour) << QVariant::fromValue((uint32_t)SpeedUnitsKnots);

        _speedUnitsMetaData->setEnumInfo(enumStrings, enumValues);
        _speedUnitsFact->setMetaData(_speedUnitsMetaData);
    }

    return _speedUnitsFact;
}
342 343 344 345 346 347 348 349

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;
}