SimpleMissionItem.cc 42.5 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8
 *
 * 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
#include <QStringList>
#include <QDebug>

14
#include "SimpleMissionItem.h"
15 16 17
#include "FirmwarePluginManager.h"
#include "QGCApplication.h"
#include "JsonHelper.h"
18 19
#include "MissionCommandTree.h"
#include "MissionCommandUIInfo.h"
20
#include "QGroundControlQmlGlobal.h"
21
#include "SettingsManager.h"
22
#include "PlanMasterController.h"
23

24 25 26 27 28 29
FactMetaData* SimpleMissionItem::_altitudeMetaData =        nullptr;
FactMetaData* SimpleMissionItem::_commandMetaData =         nullptr;
FactMetaData* SimpleMissionItem::_defaultParamMetaData =    nullptr;
FactMetaData* SimpleMissionItem::_frameMetaData =           nullptr;
FactMetaData* SimpleMissionItem::_latitudeMetaData =        nullptr;
FactMetaData* SimpleMissionItem::_longitudeMetaData =       nullptr;
30

31 32 33 34
const char* SimpleMissionItem::_jsonAltitudeModeKey =           "AltitudeMode";
const char* SimpleMissionItem::_jsonAltitudeKey =               "Altitude";
const char* SimpleMissionItem::_jsonAMSLAltAboveTerrainKey =    "AMSLAltAboveTerrain";

35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53
struct EnumInfo_s {
    const char *    label;
    MAV_FRAME       frame;
};

static const struct EnumInfo_s _rgMavFrameInfo[] = {
{ "MAV_FRAME_GLOBAL",                   MAV_FRAME_GLOBAL },
{ "MAV_FRAME_LOCAL_NED",                MAV_FRAME_LOCAL_NED },
{ "MAV_FRAME_MISSION",                  MAV_FRAME_MISSION },
{ "MAV_FRAME_GLOBAL_RELATIVE_ALT",      MAV_FRAME_GLOBAL_RELATIVE_ALT },
{ "MAV_FRAME_LOCAL_ENU",                MAV_FRAME_LOCAL_ENU },
{ "MAV_FRAME_GLOBAL_INT",               MAV_FRAME_GLOBAL_INT },
{ "MAV_FRAME_GLOBAL_RELATIVE_ALT_INT",  MAV_FRAME_GLOBAL_RELATIVE_ALT_INT },
{ "MAV_FRAME_LOCAL_OFFSET_NED",         MAV_FRAME_LOCAL_OFFSET_NED },
{ "MAV_FRAME_BODY_NED",                 MAV_FRAME_BODY_NED },
{ "MAV_FRAME_BODY_OFFSET_NED",          MAV_FRAME_BODY_OFFSET_NED },
{ "MAV_FRAME_GLOBAL_TERRAIN_ALT",       MAV_FRAME_GLOBAL_TERRAIN_ALT },
{ "MAV_FRAME_GLOBAL_TERRAIN_ALT_INT",   MAV_FRAME_GLOBAL_TERRAIN_ALT_INT },
};
54

55
SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, bool flyView, bool forLoad, QObject* parent)
56
    : VisualMissionItem                 (masterController, flyView, parent)
57 58 59 60 61 62 63 64 65 66 67
    , _commandTree                      (qgcApp()->toolbox()->missionCommandTree())
    , _supportedCommandFact             (0, "Command:",             FactMetaData::valueTypeUint32)
    , _altitudeFact                     (0, "Altitude",             FactMetaData::valueTypeDouble)
    , _amslAltAboveTerrainFact          (0, "Alt above terrain",    FactMetaData::valueTypeDouble)
    , _param1MetaData                   (FactMetaData::valueTypeDouble)
    , _param2MetaData                   (FactMetaData::valueTypeDouble)
    , _param3MetaData                   (FactMetaData::valueTypeDouble)
    , _param4MetaData                   (FactMetaData::valueTypeDouble)
    , _param5MetaData                   (FactMetaData::valueTypeDouble)
    , _param6MetaData                   (FactMetaData::valueTypeDouble)
    , _param7MetaData                   (FactMetaData::valueTypeDouble)
68
{
Don Gagne's avatar
Don Gagne committed
69
    _editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml");
70

71
    _setupMetaData();
72

73 74 75 76 77 78 79 80
    if (!forLoad) {
        // We are are going to load the SimpleItem right after this then don't connnect up signalling until after load is done
        _connectSignals();
        _updateOptionalSections();
        _setDefaultsForCommand();
        _rebuildFacts();
        setDirty(false);
    }
81 82
}

83 84
SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, bool flyView, const MissionItem& missionItem, QObject* parent)
    : VisualMissionItem         (masterController, flyView, parent)
85 86 87 88 89 90 91 92 93 94 95 96
    , _missionItem              (missionItem)
    , _commandTree              (qgcApp()->toolbox()->missionCommandTree())
    , _supportedCommandFact     (0,         "Command:",             FactMetaData::valueTypeUint32)
    , _altitudeFact             (0,         "Altitude",             FactMetaData::valueTypeDouble)
    , _amslAltAboveTerrainFact  (0,         "Alt above terrain",    FactMetaData::valueTypeDouble)
    , _param1MetaData           (FactMetaData::valueTypeDouble)
    , _param2MetaData           (FactMetaData::valueTypeDouble)
    , _param3MetaData           (FactMetaData::valueTypeDouble)
    , _param4MetaData           (FactMetaData::valueTypeDouble)
    , _param5MetaData           (FactMetaData::valueTypeDouble)
    , _param6MetaData           (FactMetaData::valueTypeDouble)
    , _param7MetaData           (FactMetaData::valueTypeDouble)
97
{
Don Gagne's avatar
Don Gagne committed
98 99
    _editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml");

100
    struct MavFrame2AltMode_s {
101 102
        MAV_FRAME                               mavFrame;
        QGroundControlQmlGlobal::AltitudeMode   altMode;
103 104 105
    };

    const struct MavFrame2AltMode_s rgMavFrame2AltMode[] = {
106 107 108 109
        { MAV_FRAME_GLOBAL_TERRAIN_ALT,     QGroundControlQmlGlobal::AltitudeModeTerrainFrame },
        { MAV_FRAME_GLOBAL,                 QGroundControlQmlGlobal::AltitudeModeAbsolute },
        { MAV_FRAME_GLOBAL_RELATIVE_ALT,    QGroundControlQmlGlobal::AltitudeModeRelative },
    };
110
    _altitudeMode = QGroundControlQmlGlobal::AltitudeModeRelative;
111 112 113 114 115 116 117 118
    for (size_t i=0; i<sizeof(rgMavFrame2AltMode)/sizeof(rgMavFrame2AltMode[0]); i++) {
        const MavFrame2AltMode_s& pMavFrame2AltMode = rgMavFrame2AltMode[i];
        if (pMavFrame2AltMode.mavFrame == missionItem.frame()) {
            _altitudeMode = pMavFrame2AltMode.altMode;
            break;
        }
    }

119
    _isCurrentItem = missionItem.isCurrentItem();
120
    _altitudeFact.setRawValue(specifiesAltitude() ? _missionItem._param7Fact.rawValue() : qQNaN());
121
    _amslAltAboveTerrainFact.setRawValue(qQNaN());
122

123 124
    // In flyView we skip some of the intialization to save memory
    if (!_flyView) {
125 126
        _setupMetaData();
    }
127
    _connectSignals();
128
    _updateOptionalSections();
129
    if (!_flyView) {
130 131
        _rebuildFacts();
    }
132 133 134

    // Signal coordinate changed to kick off terrain query
    emit coordinateChanged(coordinate());
135 136

    setDirty(false);
137 138
}

139 140 141
void SimpleMissionItem::_connectSignals(void)
{
    // Connect to change signals to track dirty state
142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167
    connect(&_missionItem._param1Fact,          &Fact::valueChanged,                        this, &SimpleMissionItem::_setDirty);
    connect(&_missionItem._param2Fact,          &Fact::valueChanged,                        this, &SimpleMissionItem::_setDirty);
    connect(&_missionItem._param3Fact,          &Fact::valueChanged,                        this, &SimpleMissionItem::_setDirty);
    connect(&_missionItem._param4Fact,          &Fact::valueChanged,                        this, &SimpleMissionItem::_setDirty);
    connect(&_missionItem._param5Fact,          &Fact::valueChanged,                        this, &SimpleMissionItem::_setDirty);
    connect(&_missionItem._param6Fact,          &Fact::valueChanged,                        this, &SimpleMissionItem::_setDirty);
    connect(&_missionItem._param7Fact,          &Fact::valueChanged,                        this, &SimpleMissionItem::_setDirty);
    connect(&_missionItem._frameFact,           &Fact::valueChanged,                        this, &SimpleMissionItem::_setDirty);
    connect(&_missionItem._commandFact,         &Fact::valueChanged,                        this, &SimpleMissionItem::_setDirty);
    connect(&_missionItem,                      &MissionItem::sequenceNumberChanged,        this, &SimpleMissionItem::_setDirty);
    connect(this,                               &SimpleMissionItem::altitudeModeChanged,    this, &SimpleMissionItem::_setDirty);

    connect(&_altitudeFact,                     &Fact::valueChanged,                        this, &SimpleMissionItem::_altitudeChanged);
    connect(this,                               &SimpleMissionItem::altitudeModeChanged,    this, &SimpleMissionItem::_altitudeModeChanged);
    connect(this,                               &SimpleMissionItem::terrainAltitudeChanged, this, &SimpleMissionItem::_terrainAltChanged);

    connect(this,                               &SimpleMissionItem::sequenceNumberChanged,  this, &SimpleMissionItem::lastSequenceNumberChanged);
    connect(this,                               &SimpleMissionItem::cameraSectionChanged,   this, &SimpleMissionItem::_setDirty);
    connect(this,                               &SimpleMissionItem::cameraSectionChanged,   this, &SimpleMissionItem::_updateLastSequenceNumber);

    connect(&_missionItem._param7Fact,          &Fact::valueChanged,                        this, &SimpleMissionItem::_amslEntryAltChanged);
    connect(this,                               &SimpleMissionItem::altitudeModeChanged,    this, &SimpleMissionItem::_amslEntryAltChanged);
    connect(this,                               &SimpleMissionItem::terrainAltitudeChanged, this, &SimpleMissionItem::_amslEntryAltChanged);
    connect(this,                               &SimpleMissionItem::amslEntryAltChanged,    this, &SimpleMissionItem::amslExitAltChanged);

    connect(this, &SimpleMissionItem::wizardModeChanged,                                    this, &SimpleMissionItem::readyForSaveStateChanged);
168

169
    // These are coordinate lat/lon values, they must emit coordinateChanged signal
170 171
    connect(&_missionItem._param5Fact,          &Fact::valueChanged,                        this, &SimpleMissionItem::_sendCoordinateChanged);
    connect(&_missionItem._param6Fact,          &Fact::valueChanged,                        this, &SimpleMissionItem::_sendCoordinateChanged);
172

173 174
    connect(&_missionItem._param1Fact,          &Fact::valueChanged,                        this, &SimpleMissionItem::_possibleAdditionalTimeDelayChanged);
    connect(&_missionItem._param4Fact,          &Fact::valueChanged,                        this, &SimpleMissionItem::_possibleVehicleYawChanged);
175

176
    // The following changes may also change friendlyEditAllowed
177 178 179
    connect(&_missionItem._autoContinueFact,    &Fact::valueChanged,                        this, &SimpleMissionItem::_sendFriendlyEditAllowedChanged);
    connect(&_missionItem._commandFact,         &Fact::valueChanged,                        this, &SimpleMissionItem::_sendFriendlyEditAllowedChanged);
    connect(&_missionItem._frameFact,           &Fact::valueChanged,                        this, &SimpleMissionItem::_sendFriendlyEditAllowedChanged);
180 181

    // A command change triggers a number of other changes as well.
182 183 184 185 186 187 188 189
    connect(&_missionItem._commandFact,         &Fact::valueChanged,                        this, &SimpleMissionItem::_setDefaultsForCommand);
    connect(&_missionItem._commandFact,         &Fact::valueChanged,                        this, &SimpleMissionItem::commandNameChanged);
    connect(&_missionItem._commandFact,         &Fact::valueChanged,                        this, &SimpleMissionItem::commandDescriptionChanged);
    connect(&_missionItem._commandFact,         &Fact::valueChanged,                        this, &SimpleMissionItem::abbreviationChanged);
    connect(&_missionItem._commandFact,         &Fact::valueChanged,                        this, &SimpleMissionItem::specifiesCoordinateChanged);
    connect(&_missionItem._commandFact,         &Fact::valueChanged,                        this, &SimpleMissionItem::specifiesAltitudeOnlyChanged);
    connect(&_missionItem._commandFact,         &Fact::valueChanged,                        this, &SimpleMissionItem::isStandaloneCoordinateChanged);
    connect(&_missionItem._commandFact,         &Fact::valueChanged,                        this, &SimpleMissionItem::isLandCommandChanged);
190 191

    // Whenever these properties change the ui model changes as well
192 193
    connect(this,                               &SimpleMissionItem::commandChanged,         this, &SimpleMissionItem::_rebuildFacts);
    connect(this,                               &SimpleMissionItem::rawEditChanged,         this, &SimpleMissionItem::_rebuildFacts);
194 195

    // These fact signals must alway signal out through SimpleMissionItem signals
196
    connect(&_missionItem._commandFact,         &Fact::valueChanged,                        this, &SimpleMissionItem::_sendCommandChanged);
197

198
    // Propogate signals from MissionItem up to SimpleMissionItem
199 200
    connect(&_missionItem,                      &MissionItem::sequenceNumberChanged,         this, &SimpleMissionItem::sequenceNumberChanged);
    connect(&_missionItem,                      &MissionItem::specifiedFlightSpeedChanged,   this, &SimpleMissionItem::specifiedFlightSpeedChanged);
201 202 203 204 205 206 207 208 209
}

void SimpleMissionItem::_setupMetaData(void)
{
    QStringList enumStrings;
    QVariantList enumValues;

    if (!_altitudeMetaData) {
        _altitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble);
210
        _altitudeMetaData->setRawUnits("m");
211
        _altitudeMetaData->setRawIncrement(1);
212 213 214 215
        _altitudeMetaData->setDecimalPlaces(2);

        enumStrings.clear();
        enumValues.clear();
216
        MissionCommandTree* commandTree = qgcApp()->toolbox()->missionCommandTree();
217
        for (const MAV_CMD command: commandTree->allCommandIds()) {
218 219
            enumStrings.append(commandTree->rawName(command));
            enumValues.append(QVariant((int)command));
220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249
        }
        _commandMetaData = new FactMetaData(FactMetaData::valueTypeUint32);
        _commandMetaData->setEnumInfo(enumStrings, enumValues);

        _defaultParamMetaData = new FactMetaData(FactMetaData::valueTypeDouble);
        _defaultParamMetaData->setDecimalPlaces(7);

        enumStrings.clear();
        enumValues.clear();
        for (size_t i=0; i<sizeof(_rgMavFrameInfo)/sizeof(_rgMavFrameInfo[0]); i++) {
            const struct EnumInfo_s* mavFrameInfo = &_rgMavFrameInfo[i];

            enumStrings.append(mavFrameInfo->label);
            enumValues.append(QVariant(mavFrameInfo->frame));
        }
        _frameMetaData = new FactMetaData(FactMetaData::valueTypeUint32);
        _frameMetaData->setEnumInfo(enumStrings, enumValues);

        _latitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble);
        _latitudeMetaData->setRawUnits("deg");
        _latitudeMetaData->setDecimalPlaces(7);

        _longitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble);
        _longitudeMetaData->setRawUnits("deg");
        _longitudeMetaData->setDecimalPlaces(7);

    }

    _missionItem._commandFact.setMetaData(_commandMetaData);
    _missionItem._frameFact.setMetaData(_frameMetaData);
250
    _altitudeFact.setMetaData(_altitudeMetaData);
251
    _amslAltAboveTerrainFact.setMetaData(_altitudeMetaData);
252 253 254 255 256 257
}

SimpleMissionItem::~SimpleMissionItem()
{    
}

258
void SimpleMissionItem::save(QJsonArray&  missionItems)
259
{
260 261 262 263 264 265 266 267
    QList<MissionItem*> items;

    appendMissionItems(items, this);

    for (int i=0; i<items.count(); i++) {
        MissionItem* item = items[i];
        QJsonObject saveObject;
        item->save(saveObject);
268 269
        if (i == 0) {
            // This is the main simple item, save the alt/terrain data
270
            if (specifiesAltitude()) {
271 272 273 274 275
                saveObject[_jsonAltitudeModeKey] =          _altitudeMode;
                saveObject[_jsonAltitudeKey] =              _altitudeFact.rawValue().toDouble();
                saveObject[_jsonAMSLAltAboveTerrainKey] =   _amslAltAboveTerrainFact.rawValue().toDouble();
            }
        }
276 277 278
        missionItems.append(saveObject);
        item->deleteLater();
    }
279 280 281 282
}

bool SimpleMissionItem::load(QTextStream &loadStream)
{
283 284
    bool success;
    if ((success = _missionItem.load(loadStream))) {
285
        if (specifiesAltitude()) {
286
            _altitudeMode = _missionItem.relativeAltitude() ? QGroundControlQmlGlobal::AltitudeModeRelative : QGroundControlQmlGlobal::AltitudeModeAbsolute;
287 288 289
            _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue());
            _amslAltAboveTerrainFact.setRawValue(qQNaN());
        }
290
        _connectSignals();
291
        _updateOptionalSections();
292 293
        _rebuildFacts();
        setDirty(false);
294
    }
295

296
    return success;
297 298
}

Don Gagne's avatar
Don Gagne committed
299
bool SimpleMissionItem::load(const QJsonObject& json, int sequenceNumber, QString& errorString)
300
{
301 302
    if (!_missionItem.load(json, sequenceNumber, errorString)) {
        return false;
303
    }
304

305
    if (specifiesAltitude()) {
306 307 308 309 310 311 312 313 314 315
        if (json.contains(_jsonAltitudeModeKey) || json.contains(_jsonAltitudeKey) || json.contains(_jsonAMSLAltAboveTerrainKey)) {
            QList<JsonHelper::KeyValidateInfo> keyInfoList = {
                { _jsonAltitudeModeKey,         QJsonValue::Double, true },
                { _jsonAltitudeKey,             QJsonValue::Double, true },
                { _jsonAMSLAltAboveTerrainKey,  QJsonValue::Double, true },
            };
            if (!JsonHelper::validateKeys(json, keyInfoList, errorString)) {
                return false;
            }

316
            _altitudeMode = (QGroundControlQmlGlobal::AltitudeMode)(int)json[_jsonAltitudeModeKey].toDouble();
317 318 319
            _altitudeFact.setRawValue(JsonHelper::possibleNaNJsonValue(json[_jsonAltitudeKey]));
            _amslAltAboveTerrainFact.setRawValue(JsonHelper::possibleNaNJsonValue(json[_jsonAltitudeKey]));
        } else {
320
            _altitudeMode = _missionItem.relativeAltitude() ? QGroundControlQmlGlobal::AltitudeModeRelative : QGroundControlQmlGlobal::AltitudeModeAbsolute;
321 322 323 324 325
            _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue());
            _amslAltAboveTerrainFact.setRawValue(qQNaN());
        }
    }

326
    _connectSignals();
327
    _updateOptionalSections();
328 329
    _rebuildFacts();
    setDirty(false);
330 331

    return true;
332 333 334 335
}

bool SimpleMissionItem::isStandaloneCoordinate(void) const
{
336
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)command());
337 338
    if (uiInfo) {
        return uiInfo->isStandaloneCoordinate();
339 340 341 342 343 344 345
    } else {
        return false;
    }
}

bool SimpleMissionItem::specifiesCoordinate(void) const
{
346
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)command());
347 348
    if (uiInfo) {
        return uiInfo->specifiesCoordinate();
349 350 351 352 353
    } else {
        return false;
    }
}

354 355
bool SimpleMissionItem::specifiesAltitudeOnly(void) const
{
356
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)command());
357 358 359 360 361 362 363
    if (uiInfo) {
        return uiInfo->specifiesAltitudeOnly();
    } else {
        return false;
    }
}

364 365
QString SimpleMissionItem::commandDescription(void) const
{
366
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)command());
367 368
    if (uiInfo) {
        return uiInfo->description();
369 370 371 372 373 374 375 376
    } else {
        qWarning() << "Should not ask for command description on unknown command";
        return commandName();
    }
}

QString SimpleMissionItem::commandName(void) const
{
377
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)command());
378 379
    if (uiInfo) {
        return uiInfo->friendlyName();
380 381
    } else {
        qWarning() << "Request for command name on unknown command";
382
        return tr("Unknown: %1").arg(command());
383 384 385
    }
}

386 387 388
QString SimpleMissionItem::abbreviation() const
{
    if (homePosition())
389
        return tr("L");
390 391

    switch(command()) {
392
    case MAV_CMD_NAV_TAKEOFF:
393
        return tr("Takeoff");
394
    case MAV_CMD_NAV_LAND:
395
        return tr("Land");
396
    case MAV_CMD_NAV_VTOL_TAKEOFF:
397
        return tr("VTOL Takeoff");
398
    case MAV_CMD_NAV_VTOL_LAND:
399
        return tr("VTOL Land");
400
    case MAV_CMD_DO_SET_ROI:
401
    case MAV_CMD_DO_SET_ROI_LOCATION:
402 403 404
        return tr("ROI");
    default:
        return QString();
405 406 407
    }
}

408
void SimpleMissionItem::_rebuildTextFieldFacts(void)
409
{
410
    _textFieldFacts.clear();
411 412
    
    if (rawEdit()) {
413
        _missionItem._param1Fact._setName("Param1");
414
        _missionItem._param1Fact.setMetaData(_defaultParamMetaData);
415
        _textFieldFacts.append(&_missionItem._param1Fact);
416
        _missionItem._param2Fact._setName("Param2");
417
        _missionItem._param2Fact.setMetaData(_defaultParamMetaData);
418
        _textFieldFacts.append(&_missionItem._param2Fact);
419
        _missionItem._param3Fact._setName("Param3");
420
        _missionItem._param3Fact.setMetaData(_defaultParamMetaData);
421
        _textFieldFacts.append(&_missionItem._param3Fact);
422
        _missionItem._param4Fact._setName("Param4");
423
        _missionItem._param4Fact.setMetaData(_defaultParamMetaData);
424
        _textFieldFacts.append(&_missionItem._param4Fact);
425
        _missionItem._param5Fact._setName("Lat/X");
426
        _missionItem._param5Fact.setMetaData(_defaultParamMetaData);
427
        _textFieldFacts.append(&_missionItem._param5Fact);
428
        _missionItem._param6Fact._setName("Lon/Y");
429
        _missionItem._param6Fact.setMetaData(_defaultParamMetaData);
430
        _textFieldFacts.append(&_missionItem._param6Fact);
431
        _missionItem._param7Fact._setName("Alt/Z");
432
        _missionItem._param7Fact.setMetaData(_defaultParamMetaData);
433
        _textFieldFacts.append(&_missionItem._param7Fact);
434
    } else {
435 436
        _ignoreDirtyChangeSignals = true;

437 438 439 440 441 442 443 444 445 446
        MAV_CMD command;
        if (_homePositionSpecialCase) {
            command = MAV_CMD_NAV_LAST;
        } else {
            command = _missionItem.command();
        }

        Fact*           rgParamFacts[7] =       { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact };
        FactMetaData*   rgParamMetaData[7] =    { &_param1MetaData, &_param2MetaData, &_param3MetaData, &_param4MetaData, &_param5MetaData, &_param6MetaData, &_param7MetaData };

447
        const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command);
448

449
        for (int i=1; i<=7; i++) {
450 451
            bool showUI;
            const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
452

453
            if (showUI && paramInfo && paramInfo->enumStrings().count() == 0 && !paramInfo->nanUnchanged()) {
454 455 456 457 458 459 460
                Fact*               paramFact =     rgParamFacts[i-1];
                FactMetaData*       paramMetaData = rgParamMetaData[i-1];

                paramFact->_setName(paramInfo->label());
                paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces());
                paramMetaData->setRawUnits(paramInfo->units());
                paramFact->setMetaData(paramMetaData);
461
                _textFieldFacts.append(paramFact);
462 463 464
            }
        }

465
        _ignoreDirtyChangeSignals = false;
466 467 468
    }
}

469
void SimpleMissionItem::_rebuildNaNFacts(void)
470
{
471 472 473 474 475 476 477 478 479 480 481 482 483 484 485
    _nanFacts.clear();

    if (!rawEdit()) {
        _ignoreDirtyChangeSignals = true;

        MAV_CMD command;
        if (_homePositionSpecialCase) {
            command = MAV_CMD_NAV_LAST;
        } else {
            command = _missionItem.command();
        }

        Fact*           rgParamFacts[7] =       { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact };
        FactMetaData*   rgParamMetaData[7] =    { &_param1MetaData, &_param2MetaData, &_param3MetaData, &_param4MetaData, &_param5MetaData, &_param6MetaData, &_param7MetaData };

486
        const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command);
487 488

        for (int i=1; i<=7; i++) {
489 490
            bool showUI;
            const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
491

492
            if (showUI && paramInfo && paramInfo->nanUnchanged()) {
493
                // Show hide Heading field on waypoint based on vehicle yaw to next waypoint setting. This needs to come from the actual vehicle if it exists
494
                // and not _controllerVehicle which is always offline.
495 496
                Vehicle* firmwareVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
                if (!firmwareVehicle) {
497
                    firmwareVehicle = _controllerVehicle;
498
                }
499
                bool hideWaypointHeading = (command == MAV_CMD_NAV_WAYPOINT || command == MAV_CMD_NAV_TAKEOFF) && (i == 4) && firmwareVehicle->firmwarePlugin()->vehicleYawsToNextWaypointInMission(firmwareVehicle);
500 501 502
                if (hideWaypointHeading) {
                    continue;
                }
503

504 505 506 507 508 509 510 511 512 513 514 515 516 517 518
                Fact*               paramFact =     rgParamFacts[i-1];
                FactMetaData*       paramMetaData = rgParamMetaData[i-1];

                paramFact->_setName(paramInfo->label());
                paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces());
                paramMetaData->setRawUnits(paramInfo->units());
                paramFact->setMetaData(paramMetaData);
                _nanFacts.append(paramFact);
            }
        }

        _ignoreDirtyChangeSignals = false;
    }
}

519
bool SimpleMissionItem::specifiesAltitude(void) const
520
{
521
    return specifiesCoordinate() || specifiesAltitudeOnly();
522 523
}

524
void SimpleMissionItem::_rebuildComboBoxFacts(void)
525
{
526
    _comboboxFacts.clear();
527 528

    if (rawEdit()) {
529 530
        _comboboxFacts.append(&_missionItem._commandFact);
        _comboboxFacts.append(&_missionItem._frameFact);
531 532 533 534 535 536 537 538 539 540 541 542
    } else {
        Fact*           rgParamFacts[7] =       { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact };
        FactMetaData*   rgParamMetaData[7] =    { &_param1MetaData, &_param2MetaData, &_param3MetaData, &_param4MetaData, &_param5MetaData, &_param6MetaData, &_param7MetaData };

        MAV_CMD command;
        if (_homePositionSpecialCase) {
            command = MAV_CMD_NAV_LAST;
        } else {
            command = (MAV_CMD)this->command();
        }

        for (int i=1; i<=7; i++) {
543
            bool showUI;
544
            const MissionCmdParamInfo* paramInfo = _commandTree->getUIInfo(_controllerVehicle, command)->getParamInfo(i, showUI);
545

546
            if (showUI && paramInfo && paramInfo->enumStrings().count() != 0) {
547 548 549 550 551 552 553 554
                Fact*               paramFact =     rgParamFacts[i-1];
                FactMetaData*       paramMetaData = rgParamMetaData[i-1];

                paramFact->_setName(paramInfo->label());
                paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces());
                paramMetaData->setEnumInfo(paramInfo->enumStrings(), paramInfo->enumValues());
                paramMetaData->setRawUnits(paramInfo->units());
                paramFact->setMetaData(paramMetaData);
555
                _comboboxFacts.append(paramFact);
556 557 558
            }
        }
    }
559
}
560

561 562 563 564 565
void SimpleMissionItem::_rebuildFacts(void)
{
    _rebuildTextFieldFacts();
    _rebuildNaNFacts();
    _rebuildComboBoxFacts();
566 567 568 569
}

bool SimpleMissionItem::friendlyEditAllowed(void) const
{
570
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, static_cast<MAV_CMD>(command()));
571
    if (uiInfo && uiInfo->friendlyEdit()) {
572 573 574 575
        if (!_missionItem.autoContinue()) {
            return false;
        }

576
        if (specifiesAltitude()) {
577 578 579 580
            MAV_FRAME frame = _missionItem.frame();
            switch (frame) {
            case MAV_FRAME_GLOBAL:
            case MAV_FRAME_GLOBAL_RELATIVE_ALT:
581
            case MAV_FRAME_GLOBAL_TERRAIN_ALT:
582
                return true;
583 584 585
            default:
                return false;
            }
586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608
        }

        return true;
    }

    return false;
}

bool SimpleMissionItem::rawEdit(void) const
{
    return _rawEdit || !friendlyEditAllowed();
}

void SimpleMissionItem::setRawEdit(bool rawEdit)
{
    if (this->rawEdit() != rawEdit) {
        _rawEdit = rawEdit;
        emit rawEditChanged(this->rawEdit());
    }
}

void SimpleMissionItem::setDirty(bool dirty)
{
609
    if (!_homePositionSpecialCase || (_dirty != dirty)) {
610
        _dirty = dirty;
611 612 613 614
        if (!dirty) {
            _cameraSection->setDirty(false);
            _speedSection->setDirty(false);
        }
615
        emit dirtyChanged(dirty);
616 617 618
    }
}

619
void SimpleMissionItem::_setDirty(void)
620
{
621 622 623
    if (!_ignoreDirtyChangeSignals) {
        setDirty(true);
    }
624 625 626 627 628 629 630
}

void SimpleMissionItem::_sendCoordinateChanged(void)
{
    emit coordinateChanged(coordinate());
}

631
void SimpleMissionItem::_altitudeModeChanged(void)
632
{
633
    switch (_altitudeMode) {
634
    case QGroundControlQmlGlobal::AltitudeModeTerrainFrame:
635 636
        _missionItem.setFrame(MAV_FRAME_GLOBAL_TERRAIN_ALT);
        break;
637
    case QGroundControlQmlGlobal::AltitudeModeAboveTerrain:
638
        // Terrain altitudes are Absolute
639
        _missionItem.setFrame(MAV_FRAME_GLOBAL);
640
        // Clear any old calculated values
641 642 643
        _missionItem._param7Fact.setRawValue(qQNaN());
        _amslAltAboveTerrainFact.setRawValue(qQNaN());
        break;
644
    case QGroundControlQmlGlobal::AltitudeModeAbsolute:
645 646
        _missionItem.setFrame(MAV_FRAME_GLOBAL);
        break;
647
    case QGroundControlQmlGlobal::AltitudeModeRelative:
648 649
        _missionItem.setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
        break;
Don Gagne's avatar
Don Gagne committed
650 651 652
    case QGroundControlQmlGlobal::AltitudeModeNone:
        qWarning() << "Internal Error SimpleMissionItem::_altitudeModeChanged: Invalid altitudeMode == AltitudeModeNone";
        break;
653
    }
654 655 656

    // We always call _altitudeChanged to make sure that param7 is always setup correctly on mode change
    _altitudeChanged();
657 658
}

659
void SimpleMissionItem::_altitudeChanged(void)
660
{
661 662 663 664
    if (!specifiesAltitude()) {
        return;
    }

665
    if (_altitudeMode == QGroundControlQmlGlobal::AltitudeModeAboveTerrain || _altitudeMode == QGroundControlQmlGlobal::AltitudeModeTerrainFrame) {
666
        _amslAltAboveTerrainFact.setRawValue(qQNaN());
667 668 669
        _terrainAltChanged();
    } else {
        _missionItem._param7Fact.setRawValue(_altitudeFact.rawValue());
670 671 672
    }
}

673 674
void SimpleMissionItem::_terrainAltChanged(void)
{
675
    if (!specifiesAltitude()) {
676 677 678 679
        // We don't need terrain data
        return;
    }

680 681 682 683 684 685 686 687 688 689 690 691
    if (_altitudeMode == QGroundControlQmlGlobal::AltitudeModeAboveTerrain) {
        if (qIsNaN(terrainAltitude())) {
            // Set NaNs to signal we are waiting on terrain data
            _missionItem._param7Fact.setRawValue(qQNaN());
            _amslAltAboveTerrainFact.setRawValue(qQNaN());
        } else {
            double newAboveTerrain = terrainAltitude() + _altitudeFact.rawValue().toDouble();
            double oldAboveTerrain = _amslAltAboveTerrainFact.rawValue().toDouble();
            if (qIsNaN(oldAboveTerrain) || !qFuzzyCompare(newAboveTerrain, oldAboveTerrain)) {
                _missionItem._param7Fact.setRawValue(newAboveTerrain);
                _amslAltAboveTerrainFact.setRawValue(newAboveTerrain);
            }
692
        }
693 694
        emit readyForSaveStateChanged();
    }
695 696
}

DonLakeFlyer's avatar
DonLakeFlyer committed
697
SimpleMissionItem::ReadyForSaveState SimpleMissionItem::readyForSaveState(void) const
698
{
699 700 701 702
    if (_wizardMode) {
        return NotReadyForSaveData;
    }

DonLakeFlyer's avatar
DonLakeFlyer committed
703 704
    bool terrainReady =  !specifiesAltitude() || !qIsNaN(_missionItem._param7Fact.rawValue().toDouble());
    return terrainReady ? ReadyForSave : NotReadyForSaveTerrain;
705 706
}

707
void SimpleMissionItem::_setDefaultsForCommand(void)
708
{
709 710 711 712 713 714 715 716 717 718
    // First reset params 1-4 to 0, we leave 5-7 alone to preserve any previous location information on command change
    _missionItem._param1Fact.setRawValue(0);
    _missionItem._param2Fact.setRawValue(0);
    _missionItem._param3Fact.setRawValue(0);
    _missionItem._param4Fact.setRawValue(0);

    if (!specifiesCoordinate() && !isStandaloneCoordinate()) {
        // No need to carry across previous lat/lon
        _missionItem._param5Fact.setRawValue(0);
        _missionItem._param6Fact.setRawValue(0);
719 720 721 722
    } else if ((specifiesCoordinate() || isStandaloneCoordinate()) && _missionItem._param5Fact.rawValue().toDouble() == 0 && _missionItem._param6Fact.rawValue().toDouble() == 0) {
        // We switched from a command without a coordinate to a command with a coordinate. Use the hint.
        _missionItem._param5Fact.setRawValue(_mapCenterHint.latitude());
        _missionItem._param6Fact.setRawValue(_mapCenterHint.longitude());
723 724 725
    }

    // Set global defaults first, then if there are param defaults they will get reset
726
    _altitudeMode = QGroundControlQmlGlobal::AltitudeModeRelative;
DonLakeFlyer's avatar
DonLakeFlyer committed
727
    emit altitudeModeChanged();
728
    _amslAltAboveTerrainFact.setRawValue(qQNaN());
729
    if (specifiesAltitude() || isStandaloneCoordinate()) {
730 731 732
        double defaultAlt = qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue().toDouble();
        _altitudeFact.setRawValue(defaultAlt);
        _missionItem._param7Fact.setRawValue(defaultAlt);
733
        setAltitudeMode(_missionController->globalAltitudeModeDefault());
734 735 736 737
    } else {
        _altitudeFact.setRawValue(0);
        _missionItem._param7Fact.setRawValue(0);
    }
738

739
    MAV_CMD command = static_cast<MAV_CMD>(this->command());
740
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command);
741 742
    if (uiInfo) {
        for (int i=1; i<=7; i++) {
743 744
            bool showUI;
            const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
745 746 747 748
            if (paramInfo) {
                Fact* rgParamFacts[7] = { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact };
                rgParamFacts[paramInfo->param()-1]->setRawValue(paramInfo->defaultValue());
            }
749 750 751
        }
    }

752
    if (command == MAV_CMD_NAV_WAYPOINT) {
753 754 755
        // We default all acceptance radius to 0. This allows flight controller to be in control of
        // accept radius.
        _missionItem.setParam2(0);
756
    } else if ((uiInfo && uiInfo->isLandCommand()) || command == MAV_CMD_DO_SET_ROI_LOCATION) {
DonLakeFlyer's avatar
DonLakeFlyer committed
757
        _altitudeFact.setRawValue(0);
758
        _missionItem.setParam7(0);
759 760 761
    }

    _missionItem.setAutoContinue(true);
762
    _missionItem.setFrame(specifiesAltitude() ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_MISSION);
763 764 765 766 767 768 769 770 771 772 773 774 775 776 777
    setRawEdit(false);
}

void SimpleMissionItem::_sendCommandChanged(void)
{
    emit commandChanged(command());
}

void SimpleMissionItem::_sendFriendlyEditAllowedChanged(void)
{
    emit friendlyEditAllowedChanged(friendlyEditAllowed());
}

QString SimpleMissionItem::category(void) const
{
778
    return _commandTree->getUIInfo(_controllerVehicle, static_cast<MAV_CMD>(command()))->category();
779 780
}

781
void SimpleMissionItem::setCommand(int command)
782
{
783 784
    if (static_cast<MAV_CMD>(command) != _missionItem.command()) {
        _missionItem.setCommand(static_cast<MAV_CMD>(command));
785
        _updateOptionalSections();
786 787 788 789 790
    }
}

void SimpleMissionItem::setCoordinate(const QGeoCoordinate& coordinate)
{
791 792 793 794
    // We only use lat/lon from coordinate. This keeps param7 and the altitude value which is kept to the side in sync.
    if (_missionItem.param5() != coordinate.latitude() || _missionItem.param6() != coordinate.longitude()) {
        _missionItem.setParam5(coordinate.latitude());
        _missionItem.setParam6(coordinate.longitude());
795 796
    }
}
797 798 799

void SimpleMissionItem::setSequenceNumber(int sequenceNumber)
{
800 801 802 803 804 805
    if (_missionItem.sequenceNumber() != sequenceNumber) {
        _missionItem.setSequenceNumber(sequenceNumber);
        emit sequenceNumberChanged(sequenceNumber);
        // This is too likely to ignore
        emit abbreviationChanged();
    }
806
}
807

DonLakeFlyer's avatar
DonLakeFlyer committed
808
double SimpleMissionItem::specifiedFlightSpeed(void)
809
{
810 811 812 813 814
    if (_speedSection->specifyFlightSpeed()) {
        return _speedSection->flightSpeed()->rawValue().toDouble();
    } else {
        return missionItem().specifiedFlightSpeed();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
815 816 817 818 819
}

double SimpleMissionItem::specifiedGimbalYaw(void)
{
    return _cameraSection->available() ? _cameraSection->specifiedGimbalYaw() : missionItem().specifiedGimbalYaw();
820
}
821

822 823 824 825 826
double SimpleMissionItem::specifiedGimbalPitch(void)
{
    return _cameraSection->available() ? _cameraSection->specifiedGimbalPitch() : missionItem().specifiedGimbalPitch();
}

827 828 829 830 831 832 833 834 835 836 837 838
double SimpleMissionItem::specifiedVehicleYaw(void)
{
    return command() == MAV_CMD_NAV_WAYPOINT ? missionItem().param4() : qQNaN();
}

void SimpleMissionItem::_possibleVehicleYawChanged(void)
{
    if (command() == MAV_CMD_NAV_WAYPOINT) {
        emit specifiedVehicleYawChanged();
    }
}

839
bool SimpleMissionItem::scanForSections(QmlObjectListModel* visualItems, int scanIndex, PlanMasterController* /*masterController*/)
840
{
841
    bool sectionFound = false;
842 843

    if (_cameraSection->available()) {
844 845 846 847
        sectionFound |= _cameraSection->scanForSection(visualItems, scanIndex);
    }
    if (_speedSection->available()) {
        sectionFound |= _speedSection->scanForSection(visualItems, scanIndex);
848
    }
849 850

    return sectionFound;
851 852
}

853
void SimpleMissionItem::_updateOptionalSections(void)
854
{
855
    // Remove previous sections
856 857
    if (_cameraSection) {
        _cameraSection->deleteLater();
858
        _cameraSection = nullptr;
859
    }
860 861
    if (_speedSection) {
        _speedSection->deleteLater();
862
        _speedSection = nullptr;
863
    }
864

865 866
    // Add new sections

867 868
    _cameraSection = new CameraSection(_masterController, this);
    _speedSection = new SpeedSection(_masterController, this);
869
    if (static_cast<MAV_CMD>(command()) == MAV_CMD_NAV_WAYPOINT) {
870
        _cameraSection->setAvailable(true);
871
        _speedSection->setAvailable(true);
872 873
    }

874 875 876 877 878 879
    connect(_cameraSection, &CameraSection::dirtyChanged,                   this, &SimpleMissionItem::_sectionDirtyChanged);
    connect(_cameraSection, &CameraSection::itemCountChanged,               this, &SimpleMissionItem::_updateLastSequenceNumber);
    connect(_cameraSection, &CameraSection::availableChanged,               this, &SimpleMissionItem::specifiedGimbalYawChanged);
    connect(_cameraSection, &CameraSection::availableChanged,               this, &SimpleMissionItem::specifiedGimbalPitchChanged);
    connect(_cameraSection, &CameraSection::specifiedGimbalPitchChanged,    this, &SimpleMissionItem::specifiedGimbalPitchChanged);
    connect(_cameraSection, &CameraSection::specifiedGimbalYawChanged,      this, &SimpleMissionItem::specifiedGimbalYawChanged);
880

881 882 883
    connect(_speedSection,  &SpeedSection::dirtyChanged,                this, &SimpleMissionItem::_sectionDirtyChanged);
    connect(_speedSection,  &SpeedSection::itemCountChanged,            this, &SimpleMissionItem::_updateLastSequenceNumber);
    connect(_speedSection,  &SpeedSection::specifiedFlightSpeedChanged, this, &SimpleMissionItem::specifiedFlightSpeedChanged);
884

885
    emit cameraSectionChanged(_cameraSection);
886
    emit speedSectionChanged(_speedSection);
887
    emit lastSequenceNumberChanged(lastSequenceNumber());
888 889 890 891
}

int SimpleMissionItem::lastSequenceNumber(void) const
{
892
    return sequenceNumber() + (_cameraSection ? _cameraSection->itemCount() : 0) + (_speedSection ? _speedSection->itemCount() : 0);
893 894 895 896 897 898 899
}

void SimpleMissionItem::_updateLastSequenceNumber(void)
{
    emit lastSequenceNumberChanged(lastSequenceNumber());
}

900
void SimpleMissionItem::_sectionDirtyChanged(bool dirty)
901 902 903 904 905 906 907 908 909 910 911 912 913
{
    if (dirty) {
        setDirty(true);
    }
}

void SimpleMissionItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{
    int seqNum = sequenceNumber();

    items.append(new MissionItem(missionItem(), missionItemParent));
    seqNum++;

914 915
    _cameraSection->appendSectionItems(items, missionItemParent, seqNum);
    _speedSection->appendSectionItems(items, missionItemParent, seqNum);
916
}
DonLakeFlyer's avatar
DonLakeFlyer committed
917 918 919

void SimpleMissionItem::applyNewAltitude(double newAltitude)
{
920
    MAV_CMD command = static_cast<MAV_CMD>(this->command());
921
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command);
DonLakeFlyer's avatar
DonLakeFlyer committed
922 923

    if (uiInfo->specifiesCoordinate() || uiInfo->specifiesAltitudeOnly()) {
924
        switch (static_cast<MAV_CMD>(this->command())) {
DonLakeFlyer's avatar
DonLakeFlyer committed
925 926 927 928 929
        case MAV_CMD_NAV_LAND:
        case MAV_CMD_NAV_VTOL_LAND:
            // Leave alone
            break;
        default:
930
            _altitudeFact.setRawValue(newAltitude);
DonLakeFlyer's avatar
DonLakeFlyer committed
931 932 933 934
            break;
        }
    }
}
935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951

void SimpleMissionItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus)
{
    // If user has not already set speed/gimbal, set defaults from previous items.
    VisualMissionItem::setMissionFlightStatus(missionFlightStatus);
    if (_speedSection->available() && !_speedSection->specifyFlightSpeed() && !qFuzzyCompare(_speedSection->flightSpeed()->rawValue().toDouble(), missionFlightStatus.vehicleSpeed)) {
        _speedSection->flightSpeed()->setRawValue(missionFlightStatus.vehicleSpeed);
    }
    if (_cameraSection->available() && !_cameraSection->specifyGimbal()) {
        if (!qIsNaN(missionFlightStatus.gimbalYaw) && !qFuzzyCompare(_cameraSection->gimbalYaw()->rawValue().toDouble(), missionFlightStatus.gimbalYaw)) {
            _cameraSection->gimbalYaw()->setRawValue(missionFlightStatus.gimbalYaw);
        }
        if (!qIsNaN(missionFlightStatus.gimbalPitch) && !qFuzzyCompare(_cameraSection->gimbalPitch()->rawValue().toDouble(), missionFlightStatus.gimbalPitch)) {
            _cameraSection->gimbalPitch()->setRawValue(missionFlightStatus.gimbalPitch);
        }
    }
}
952

953
void SimpleMissionItem::setAltitudeMode(QGroundControlQmlGlobal::AltitudeMode altitudeMode)
954 955 956 957 958 959
{
    if (altitudeMode != _altitudeMode) {
        _altitudeMode = altitudeMode;
        emit altitudeModeChanged();
    }
}
960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984

double SimpleMissionItem::additionalTimeDelay(void) const
{
    switch (command()) {
    case MAV_CMD_NAV_WAYPOINT:
    case MAV_CMD_CONDITION_DELAY:
    case MAV_CMD_NAV_DELAY:
        return missionItem().param1();
    default:
        return 0;
    }
}

void SimpleMissionItem::_possibleAdditionalTimeDelayChanged(void)
{
    switch (command()) {
    case MAV_CMD_NAV_WAYPOINT:
    case MAV_CMD_CONDITION_DELAY:
    case MAV_CMD_NAV_DELAY:
        emit additionalTimeDelayChanged();
        break;
    }

    return;
}
985 986 987 988

bool SimpleMissionItem::isLandCommand(void) const
{
    MAV_CMD command = static_cast<MAV_CMD>(this->command());
989
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command);
990 991
    return uiInfo->isLandCommand();
}
992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005

QGeoCoordinate SimpleMissionItem::coordinate(void) const
{
    if (qIsNaN(_missionItem.param5()) || qIsNaN(_missionItem.param6())) {
        return QGeoCoordinate();
    } else {
        return QGeoCoordinate(_missionItem.param5(), _missionItem.param6());
    }
}

double SimpleMissionItem::amslEntryAlt(void) const
{
    switch (_altitudeMode) {
    case QGroundControlQmlGlobal::AltitudeModeTerrainFrame:
1006
        return _missionItem.param7() + _terrainAltitude;
1007 1008 1009 1010 1011
    case QGroundControlQmlGlobal::AltitudeModeAboveTerrain:
    case QGroundControlQmlGlobal::AltitudeModeAbsolute:
        return _missionItem.param7();
    case QGroundControlQmlGlobal::AltitudeModeRelative:
        return _missionItem.param7() + _masterController->missionController()->plannedHomePosition().altitude();
1012 1013 1014
    case QGroundControlQmlGlobal::AltitudeModeNone:
        qWarning() << "Internal Error SimpleMissionItem::amslEntryAlt: Invalid altitudeMode:AltitudeModeNone";
        return qQNaN();
1015
    }
1016 1017 1018

    qWarning() << "Internal Error SimpleMissionItem::amslEntryAlt: Invalid altitudeMode:" << _altitudeMode;
    return qQNaN();
1019
}