SimpleMissionItem.cc 39.9 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
        { MAV_FRAME_GLOBAL_TERRAIN_ALT,     QGroundControlQmlGlobal::AltitudeModeTerrainFrame },
        { MAV_FRAME_GLOBAL,                 QGroundControlQmlGlobal::AltitudeModeAbsolute },
        { MAV_FRAME_GLOBAL_RELATIVE_ALT,    QGroundControlQmlGlobal::AltitudeModeRelative },
109
    };
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(specifiesCoordinate() || specifiesAltitudeOnly() ? _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
    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);
157

158 159 160 161
    connect(this, &SimpleMissionItem::sequenceNumberChanged,        this, &SimpleMissionItem::lastSequenceNumberChanged);
    connect(this, &SimpleMissionItem::cameraSectionChanged,         this, &SimpleMissionItem::_setDirty);
    connect(this, &SimpleMissionItem::cameraSectionChanged,         this, &SimpleMissionItem::_updateLastSequenceNumber);

162 163
    connect(this, &SimpleMissionItem::wizardModeChanged,             this, &SimpleMissionItem::readyForSaveStateChanged);

164
    // These are coordinate parameters, they must emit coordinateChanged signal
165 166 167
    connect(&_missionItem._param5Fact,  &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged);
    connect(&_missionItem._param6Fact,  &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged);
    connect(&_missionItem._param7Fact,  &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged);
168

169
    connect(&_missionItem._param1Fact,  &Fact::valueChanged, this, &SimpleMissionItem::_possibleAdditionalTimeDelayChanged);
170
    connect(&_missionItem._param4Fact,  &Fact::valueChanged, this, &SimpleMissionItem::_possibleVehicleYawChanged);
171

172 173 174 175 176 177
    // The following changes may also change friendlyEditAllowed
    connect(&_missionItem._autoContinueFact,    &Fact::valueChanged, this, &SimpleMissionItem::_sendFriendlyEditAllowedChanged);
    connect(&_missionItem._commandFact,         &Fact::valueChanged, this, &SimpleMissionItem::_sendFriendlyEditAllowedChanged);
    connect(&_missionItem._frameFact,           &Fact::valueChanged, this, &SimpleMissionItem::_sendFriendlyEditAllowedChanged);

    // A command change triggers a number of other changes as well.
178
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::_setDefaultsForCommand);
179 180
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::commandNameChanged);
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::commandDescriptionChanged);
181
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::abbreviationChanged);
182
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::specifiesCoordinateChanged);
183
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::specifiesAltitudeOnlyChanged);
184 185 186
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::isStandaloneCoordinateChanged);

    // Whenever these properties change the ui model changes as well
187 188
    connect(this, &SimpleMissionItem::commandChanged,       this, &SimpleMissionItem::_rebuildFacts);
    connect(this, &SimpleMissionItem::rawEditChanged,       this, &SimpleMissionItem::_rebuildFacts);
189 190 191

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

193 194 195
    // Propogate signals from MissionItem up to SimpleMissionItem
    connect(&_missionItem, &MissionItem::sequenceNumberChanged,         this, &SimpleMissionItem::sequenceNumberChanged);
    connect(&_missionItem, &MissionItem::specifiedFlightSpeedChanged,   this, &SimpleMissionItem::specifiedFlightSpeedChanged);
196 197 198 199 200 201 202 203 204
}

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

    if (!_altitudeMetaData) {
        _altitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble);
205
        _altitudeMetaData->setRawUnits("m");
206
        _altitudeMetaData->setRawIncrement(1);
207 208 209 210
        _altitudeMetaData->setDecimalPlaces(2);

        enumStrings.clear();
        enumValues.clear();
211
        MissionCommandTree* commandTree = qgcApp()->toolbox()->missionCommandTree();
212
        for (const MAV_CMD command: commandTree->allCommandIds()) {
213 214
            enumStrings.append(commandTree->rawName(command));
            enumValues.append(QVariant((int)command));
215 216 217 218 219 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
        }
        _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);
245
    _altitudeFact.setMetaData(_altitudeMetaData);
246
    _amslAltAboveTerrainFact.setMetaData(_altitudeMetaData);
247 248 249 250 251 252
}

SimpleMissionItem::~SimpleMissionItem()
{    
}

253
void SimpleMissionItem::save(QJsonArray&  missionItems)
254
{
255 256 257 258 259 260 261 262
    QList<MissionItem*> items;

    appendMissionItems(items, this);

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

bool SimpleMissionItem::load(QTextStream &loadStream)
{
278 279
    bool success;
    if ((success = _missionItem.load(loadStream))) {
280
        if (specifiesCoordinate()) {
281
            _altitudeMode = _missionItem.relativeAltitude() ? QGroundControlQmlGlobal::AltitudeModeRelative : QGroundControlQmlGlobal::AltitudeModeAbsolute;
282 283 284
            _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue());
            _amslAltAboveTerrainFact.setRawValue(qQNaN());
        }
285
        _connectSignals();
286
        _updateOptionalSections();
287 288
        _rebuildFacts();
        setDirty(false);
289
    }
290

291
    return success;
292 293
}

Don Gagne's avatar
Don Gagne committed
294
bool SimpleMissionItem::load(const QJsonObject& json, int sequenceNumber, QString& errorString)
295
{
296 297
    if (!_missionItem.load(json, sequenceNumber, errorString)) {
        return false;
298
    }
299 300 301 302 303 304 305 306 307 308 309 310

    if (specifiesCoordinate()) {
        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;
            }

311
            _altitudeMode = (QGroundControlQmlGlobal::AltitudeMode)(int)json[_jsonAltitudeModeKey].toDouble();
312 313 314
            _altitudeFact.setRawValue(JsonHelper::possibleNaNJsonValue(json[_jsonAltitudeKey]));
            _amslAltAboveTerrainFact.setRawValue(JsonHelper::possibleNaNJsonValue(json[_jsonAltitudeKey]));
        } else {
315
            _altitudeMode = _missionItem.relativeAltitude() ? QGroundControlQmlGlobal::AltitudeModeRelative : QGroundControlQmlGlobal::AltitudeModeAbsolute;
316 317 318 319 320
            _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue());
            _amslAltAboveTerrainFact.setRawValue(qQNaN());
        }
    }

321
    _connectSignals();
322
    _updateOptionalSections();
323 324
    _rebuildFacts();
    setDirty(false);
325 326

    return true;
327 328 329 330
}

bool SimpleMissionItem::isStandaloneCoordinate(void) const
{
331
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)command());
332 333
    if (uiInfo) {
        return uiInfo->isStandaloneCoordinate();
334 335 336 337 338 339 340
    } else {
        return false;
    }
}

bool SimpleMissionItem::specifiesCoordinate(void) const
{
341
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)command());
342 343
    if (uiInfo) {
        return uiInfo->specifiesCoordinate();
344 345 346 347 348
    } else {
        return false;
    }
}

349 350
bool SimpleMissionItem::specifiesAltitudeOnly(void) const
{
351
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)command());
352 353 354 355 356 357 358
    if (uiInfo) {
        return uiInfo->specifiesAltitudeOnly();
    } else {
        return false;
    }
}

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

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

381 382 383
QString SimpleMissionItem::abbreviation() const
{
    if (homePosition())
384
        return tr("L");
385 386

    switch(command()) {
387
    case MAV_CMD_NAV_TAKEOFF:
388
        return tr("Takeoff");
389
    case MAV_CMD_NAV_LAND:
390
        return tr("Land");
391
    case MAV_CMD_NAV_VTOL_TAKEOFF:
392
        return tr("VTOL Takeoff");
393
    case MAV_CMD_NAV_VTOL_LAND:
394
        return tr("VTOL Land");
395
    case MAV_CMD_DO_SET_ROI:
396
    case MAV_CMD_DO_SET_ROI_LOCATION:
397 398 399
        return tr("ROI");
    default:
        return QString();
400 401 402
    }
}

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

432 433 434 435 436 437 438 439 440 441
        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 };

442
        const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command);
443

444
        for (int i=1; i<=7; i++) {
445 446
            bool showUI;
            const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
447

448
            if (showUI && paramInfo && paramInfo->enumStrings().count() == 0 && !paramInfo->nanUnchanged()) {
449 450 451 452 453 454 455
                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);
456
                _textFieldFacts.append(paramFact);
457 458 459
            }
        }

460
        _ignoreDirtyChangeSignals = false;
461 462 463
    }
}

464
void SimpleMissionItem::_rebuildNaNFacts(void)
465
{
466 467 468 469 470 471 472 473 474 475 476 477 478 479 480
    _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 };

481
        const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command);
482 483

        for (int i=1; i<=7; i++) {
484 485
            bool showUI;
            const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
486

487
            if (showUI && paramInfo && paramInfo->nanUnchanged()) {
488
                // 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
489
                // and not _controllerVehicle which is always offline.
490 491
                Vehicle* firmwareVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
                if (!firmwareVehicle) {
492
                    firmwareVehicle = _controllerVehicle;
493
                }
494
                bool hideWaypointHeading = (command == MAV_CMD_NAV_WAYPOINT || command == MAV_CMD_NAV_TAKEOFF) && (i == 4) && firmwareVehicle->firmwarePlugin()->vehicleYawsToNextWaypointInMission(firmwareVehicle);
495 496 497
                if (hideWaypointHeading) {
                    continue;
                }
498

499 500 501 502 503 504 505 506 507 508 509 510 511 512 513
                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;
    }
}

514
bool SimpleMissionItem::specifiesAltitude(void) const
515
{
516
    return specifiesCoordinate() || specifiesAltitudeOnly();
517 518
}

519
void SimpleMissionItem::_rebuildComboBoxFacts(void)
520
{
521
    _comboboxFacts.clear();
522 523

    if (rawEdit()) {
524 525
        _comboboxFacts.append(&_missionItem._commandFact);
        _comboboxFacts.append(&_missionItem._frameFact);
526 527 528 529 530 531 532 533 534 535 536 537
    } 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++) {
538
            bool showUI;
539
            const MissionCmdParamInfo* paramInfo = _commandTree->getUIInfo(_controllerVehicle, command)->getParamInfo(i, showUI);
540

541
            if (showUI && paramInfo && paramInfo->enumStrings().count() != 0) {
542 543 544 545 546 547 548 549
                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);
550
                _comboboxFacts.append(paramFact);
551 552 553
            }
        }
    }
554
}
555

556 557 558 559 560
void SimpleMissionItem::_rebuildFacts(void)
{
    _rebuildTextFieldFacts();
    _rebuildNaNFacts();
    _rebuildComboBoxFacts();
561 562 563 564
}

bool SimpleMissionItem::friendlyEditAllowed(void) const
{
565
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, static_cast<MAV_CMD>(command()));
566
    if (uiInfo && uiInfo->friendlyEdit()) {
567 568 569 570
        if (!_missionItem.autoContinue()) {
            return false;
        }

571
        if (specifiesCoordinate() || specifiesAltitudeOnly()) {
572 573 574 575
            MAV_FRAME frame = _missionItem.frame();
            switch (frame) {
            case MAV_FRAME_GLOBAL:
            case MAV_FRAME_GLOBAL_RELATIVE_ALT:
576
            case MAV_FRAME_GLOBAL_TERRAIN_ALT:
577
                return true;
578 579 580
            default:
                return false;
            }
581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603
        }

        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)
{
604
    if (!_homePositionSpecialCase || (_dirty != dirty)) {
605
        _dirty = dirty;
606 607 608 609
        if (!dirty) {
            _cameraSection->setDirty(false);
            _speedSection->setDirty(false);
        }
610
        emit dirtyChanged(dirty);
611 612 613
    }
}

614
void SimpleMissionItem::_setDirty(void)
615
{
616 617 618
    if (!_ignoreDirtyChangeSignals) {
        setDirty(true);
    }
619 620 621 622 623 624 625
}

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

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

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

653
    emit coordinateHasRelativeAltitudeChanged(_altitudeMode == QGroundControlQmlGlobal::AltitudeModeRelative);
654 655
}

656
void SimpleMissionItem::_altitudeChanged(void)
657
{
658 659 660 661
    if (!specifiesAltitude()) {
        return;
    }

662
    if (_altitudeMode == QGroundControlQmlGlobal::AltitudeModeAboveTerrain) {
663
        _amslAltAboveTerrainFact.setRawValue(qQNaN());
664 665 666
        _terrainAltChanged();
    } else {
        _missionItem._param7Fact.setRawValue(_altitudeFact.rawValue());
667 668 669
    }
}

670 671
void SimpleMissionItem::_terrainAltChanged(void)
{
672
    if (!specifiesAltitude() || _altitudeMode != QGroundControlQmlGlobal::AltitudeModeAboveTerrain) {
673 674 675 676 677 678 679 680 681
        // We don't need terrain data
        return;
    }

    if (qIsNaN(terrainAltitude())) {
        // Set NaNs to signal we are waiting on terrain data
        _missionItem._param7Fact.setRawValue(qQNaN());
        _amslAltAboveTerrainFact.setRawValue(qQNaN());
    } else {
682 683 684 685 686 687
        double newAboveTerrain = terrainAltitude() + _altitudeFact.rawValue().toDouble();
        double oldAboveTerrain = _amslAltAboveTerrainFact.rawValue().toDouble();
        if (qIsNaN(oldAboveTerrain) || !qFuzzyCompare(newAboveTerrain, oldAboveTerrain)) {
            _missionItem._param7Fact.setRawValue(newAboveTerrain);
            _amslAltAboveTerrainFact.setRawValue(newAboveTerrain);
        }
688
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
689
    emit readyForSaveStateChanged();
690 691
}

DonLakeFlyer's avatar
DonLakeFlyer committed
692
SimpleMissionItem::ReadyForSaveState SimpleMissionItem::readyForSaveState(void) const
693
{
694 695 696 697
    if (_wizardMode) {
        return NotReadyForSaveData;
    }

DonLakeFlyer's avatar
DonLakeFlyer committed
698 699
    bool terrainReady =  !specifiesAltitude() || !qIsNaN(_missionItem._param7Fact.rawValue().toDouble());
    return terrainReady ? ReadyForSave : NotReadyForSaveTerrain;
700 701
}

702
void SimpleMissionItem::_setDefaultsForCommand(void)
703
{
704 705 706 707 708 709 710 711 712 713
    // 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);
714 715 716 717
    } 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());
718 719 720
    }

    // Set global defaults first, then if there are param defaults they will get reset
721
    _altitudeMode = QGroundControlQmlGlobal::AltitudeModeRelative;
DonLakeFlyer's avatar
DonLakeFlyer committed
722
    emit altitudeModeChanged();
723
    _amslAltAboveTerrainFact.setRawValue(qQNaN());
724 725 726 727 728 729 730 731
    if (specifiesCoordinate() || isStandaloneCoordinate() || specifiesAltitudeOnly()) {
        double defaultAlt = qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue().toDouble();
        _altitudeFact.setRawValue(defaultAlt);
        _missionItem._param7Fact.setRawValue(defaultAlt);
    } else {
        _altitudeFact.setRawValue(0);
        _missionItem._param7Fact.setRawValue(0);
    }
732

733
    MAV_CMD command = static_cast<MAV_CMD>(this->command());
734
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command);
735 736
    if (uiInfo) {
        for (int i=1; i<=7; i++) {
737 738
            bool showUI;
            const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
739 740 741 742
            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());
            }
743 744 745
        }
    }

746 747
    switch (command) {
    case MAV_CMD_NAV_WAYPOINT:
748 749 750
        // We default all acceptance radius to 0. This allows flight controller to be in control of
        // accept radius.
        _missionItem.setParam2(0);
751 752 753
        break;

    case MAV_CMD_NAV_LAND:
Don Gagne's avatar
Don Gagne committed
754
    case MAV_CMD_NAV_VTOL_LAND:
Don Gagne's avatar
Don Gagne committed
755
    case MAV_CMD_DO_SET_ROI_LOCATION:
DonLakeFlyer's avatar
DonLakeFlyer committed
756
        _altitudeFact.setRawValue(0);
757 758
        _missionItem.setParam7(0);
        break;
Donald Gagne's avatar
Donald Gagne committed
759 760
    default:
        break;
761 762 763
    }

    _missionItem.setAutoContinue(true);
764
    _missionItem.setFrame((specifiesCoordinate() || specifiesAltitudeOnly()) ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_MISSION);
765 766 767 768 769 770 771 772 773 774 775 776 777 778 779
    setRawEdit(false);
}

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

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

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

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

void SimpleMissionItem::setCoordinate(const QGeoCoordinate& coordinate)
{
793 794 795 796
    // 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());
797 798
    }
}
799 800 801

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

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

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

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

829 830 831 832 833 834 835 836 837 838 839 840
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();
    }
}

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

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

    return sectionFound;
853 854
}

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

867 868
    // Add new sections

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

876 877 878 879 880 881
    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);
882

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

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

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

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

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

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

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

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

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

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

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

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

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