SimpleMissionItem.cc 39.7 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
9 10


11 12 13
#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

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

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

34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52
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 },
};
53

54 55
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* parent)
    : VisualMissionItem                 (vehicle, flyView, parent)
56 57 58
    , _rawEdit                          (false)
    , _dirty                            (false)
    , _ignoreDirtyChangeSignals         (false)
59 60
    , _speedSection                     (nullptr)
    , _cameraSection                    (nullptr)
61 62
    , _commandTree                      (qgcApp()->toolbox()->missionCommandTree())
    , _supportedCommandFact             (0, "Command:",             FactMetaData::valueTypeUint32)
63
    , _altitudeMode                     (QGroundControlQmlGlobal::AltitudeModeRelative)
64 65 66 67 68 69 70 71 72 73
    , _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)
    , _syncingHeadingDegreesAndParam4   (false)
74
{
Don Gagne's avatar
Don Gagne committed
75
    _editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml");
76

77 78
    _setupMetaData();
    _connectSignals();
79
    _updateOptionalSections();
80

81
    _setDefaultsForCommand();
82
    _rebuildFacts();
83 84

    setDirty(false);
85 86
}

87 88
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, const MissionItem& missionItem, QObject* parent)
    : VisualMissionItem         (vehicle, flyView, parent)
89 90 91 92
    , _missionItem              (missionItem)
    , _rawEdit                  (false)
    , _dirty                    (false)
    , _ignoreDirtyChangeSignals (false)
93 94
    , _speedSection             (nullptr)
    , _cameraSection            (nullptr)
95 96 97 98 99 100 101 102 103 104 105
    , _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)
106
    , _syncingHeadingDegreesAndParam4           (false)
107
{
Don Gagne's avatar
Don Gagne committed
108 109
    _editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml");

110
    struct MavFrame2AltMode_s {
111 112
        MAV_FRAME                               mavFrame;
        QGroundControlQmlGlobal::AltitudeMode   altMode;
113 114 115
    };

    const struct MavFrame2AltMode_s rgMavFrame2AltMode[] = {
116 117 118
        { MAV_FRAME_GLOBAL_TERRAIN_ALT,     QGroundControlQmlGlobal::AltitudeModeTerrainFrame },
        { MAV_FRAME_GLOBAL,                 QGroundControlQmlGlobal::AltitudeModeAbsolute },
        { MAV_FRAME_GLOBAL_RELATIVE_ALT,    QGroundControlQmlGlobal::AltitudeModeRelative },
119
    };
120
    _altitudeMode = QGroundControlQmlGlobal::AltitudeModeRelative;
121 122 123 124 125 126 127 128
    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;
        }
    }

129
    _isCurrentItem = missionItem.isCurrentItem();
130
    _altitudeFact.setRawValue(specifiesCoordinate() || specifiesAltitudeOnly() ? _missionItem._param7Fact.rawValue() : qQNaN());
131
    _amslAltAboveTerrainFact.setRawValue(qQNaN());
132

133 134
    // In flyView we skip some of the intialization to save memory
    if (!_flyView) {
135 136
        _setupMetaData();
    }
137
    _connectSignals();
138
    _updateOptionalSections();
139
    if (!_flyView) {
140 141
        _rebuildFacts();
    }
142 143 144

    // Signal coordinate changed to kick off terrain query
    emit coordinateChanged(coordinate());
145 146

    setDirty(false);
147 148
}

149 150 151
void SimpleMissionItem::_connectSignals(void)
{
    // Connect to change signals to track dirty state
152 153 154 155 156 157 158 159 160 161 162 163 164 165 166
    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);
167

168 169 170 171
    connect(this, &SimpleMissionItem::sequenceNumberChanged,        this, &SimpleMissionItem::lastSequenceNumberChanged);
    connect(this, &SimpleMissionItem::cameraSectionChanged,         this, &SimpleMissionItem::_setDirty);
    connect(this, &SimpleMissionItem::cameraSectionChanged,         this, &SimpleMissionItem::_updateLastSequenceNumber);

172 173
    connect(this, &SimpleMissionItem::wizardModeChanged,             this, &SimpleMissionItem::readyForSaveStateChanged);

174
    // These are coordinate parameters, they must emit coordinateChanged signal
175 176 177
    connect(&_missionItem._param5Fact,  &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged);
    connect(&_missionItem._param6Fact,  &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged);
    connect(&_missionItem._param7Fact,  &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged);
178

179 180
    connect(&_missionItem._param1Fact,  &Fact::valueChanged, this, &SimpleMissionItem::_possibleAdditionalTimeDelayChanged);

181 182 183 184 185 186
    // 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.
187
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::_setDefaultsForCommand);
188 189
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::commandNameChanged);
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::commandDescriptionChanged);
190
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::abbreviationChanged);
191
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::specifiesCoordinateChanged);
192
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::specifiesAltitudeOnlyChanged);
193 194 195
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::isStandaloneCoordinateChanged);

    // Whenever these properties change the ui model changes as well
196 197
    connect(this, &SimpleMissionItem::commandChanged,       this, &SimpleMissionItem::_rebuildFacts);
    connect(this, &SimpleMissionItem::rawEditChanged,       this, &SimpleMissionItem::_rebuildFacts);
198 199 200

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

202 203 204 205 206 207
    // Propogate signals from MissionItem up to SimpleMissionItem
    connect(&_missionItem, &MissionItem::sequenceNumberChanged,         this, &SimpleMissionItem::sequenceNumberChanged);
    connect(&_missionItem, &MissionItem::specifiedFlightSpeedChanged,   this, &SimpleMissionItem::specifiedFlightSpeedChanged);

    // Firmware type change can affect supportsTerrainFrame
    connect(_vehicle, &Vehicle::firmwareTypeChanged, this, &SimpleMissionItem::supportsTerrainFrameChanged);
208 209 210 211 212 213 214 215 216
}

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

    if (!_altitudeMetaData) {
        _altitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble);
217
        _altitudeMetaData->setRawUnits("m");
218
        _altitudeMetaData->setRawIncrement(1);
219 220 221 222
        _altitudeMetaData->setDecimalPlaces(2);

        enumStrings.clear();
        enumValues.clear();
223
        MissionCommandTree* commandTree = qgcApp()->toolbox()->missionCommandTree();
224
        for (const MAV_CMD command: commandTree->allCommandIds()) {
225 226
            enumStrings.append(commandTree->rawName(command));
            enumValues.append(QVariant((int)command));
227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256
        }
        _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);
257
    _altitudeFact.setMetaData(_altitudeMetaData);
258
    _amslAltAboveTerrainFact.setMetaData(_altitudeMetaData);
259 260 261 262 263 264
}

SimpleMissionItem::~SimpleMissionItem()
{    
}

265
void SimpleMissionItem::save(QJsonArray&  missionItems)
266
{
267 268 269 270 271 272 273 274
    QList<MissionItem*> items;

    appendMissionItems(items, this);

    for (int i=0; i<items.count(); i++) {
        MissionItem* item = items[i];
        QJsonObject saveObject;
        item->save(saveObject);
275 276 277 278 279 280 281 282
        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();
            }
        }
283 284 285
        missionItems.append(saveObject);
        item->deleteLater();
    }
286 287 288 289
}

bool SimpleMissionItem::load(QTextStream &loadStream)
{
290 291
    bool success;
    if ((success = _missionItem.load(loadStream))) {
292
        if (specifiesCoordinate()) {
293
            _altitudeMode = _missionItem.relativeAltitude() ? QGroundControlQmlGlobal::AltitudeModeRelative : QGroundControlQmlGlobal::AltitudeModeAbsolute;
294 295 296
            _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue());
            _amslAltAboveTerrainFact.setRawValue(qQNaN());
        }
297 298
        _updateOptionalSections();
    }
299

300
    return success;
301 302
}

Don Gagne's avatar
Don Gagne committed
303
bool SimpleMissionItem::load(const QJsonObject& json, int sequenceNumber, QString& errorString)
304
{
305 306
    if (!_missionItem.load(json, sequenceNumber, errorString)) {
        return false;
307
    }
308 309 310 311 312 313 314 315 316 317 318 319

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

320
            _altitudeMode = (QGroundControlQmlGlobal::AltitudeMode)(int)json[_jsonAltitudeModeKey].toDouble();
321 322 323
            _altitudeFact.setRawValue(JsonHelper::possibleNaNJsonValue(json[_jsonAltitudeKey]));
            _amslAltAboveTerrainFact.setRawValue(JsonHelper::possibleNaNJsonValue(json[_jsonAltitudeKey]));
        } else {
324
            _altitudeMode = _missionItem.relativeAltitude() ? QGroundControlQmlGlobal::AltitudeModeRelative : QGroundControlQmlGlobal::AltitudeModeAbsolute;
325 326 327 328 329 330 331 332
            _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue());
            _amslAltAboveTerrainFact.setRawValue(qQNaN());
        }
    }

    _updateOptionalSections();

    return true;
333 334 335 336
}

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

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

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

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

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

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

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

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

438 439 440 441 442 443 444 445 446 447
        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 };

448 449
        const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, command);

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

454
            if (showUI && paramInfo && paramInfo->enumStrings().count() == 0 && !paramInfo->nanUnchanged()) {
455 456 457 458 459 460 461
                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);
462
                _textFieldFacts.append(paramFact);
463 464 465
            }
        }

466
        _ignoreDirtyChangeSignals = false;
467 468 469
    }
}

470
void SimpleMissionItem::_rebuildNaNFacts(void)
471
{
472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489
    _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 };

        const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, command);

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

493
            if (showUI && paramInfo && paramInfo->nanUnchanged()) {
494 495 496 497 498 499
                // 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
                // and not _vehicle which is always offline.
                Vehicle* firmwareVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
                if (!firmwareVehicle) {
                    firmwareVehicle = _vehicle;
                }
500
                bool hideWaypointHeading = (command == MAV_CMD_NAV_WAYPOINT || command == MAV_CMD_NAV_TAKEOFF) && (i == 4) && firmwareVehicle->firmwarePlugin()->vehicleYawsToNextWaypointInMission(firmwareVehicle);
501 502 503
                if (hideWaypointHeading) {
                    continue;
                }
504

505 506 507 508 509 510 511 512 513 514 515 516 517 518 519
                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;
    }
}

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

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

    if (rawEdit()) {
530 531
        _comboboxFacts.append(&_missionItem._commandFact);
        _comboboxFacts.append(&_missionItem._frameFact);
532 533 534 535 536 537 538 539 540 541 542 543
    } 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++) {
544 545
            bool showUI;
            const MissionCmdParamInfo* paramInfo = _commandTree->getUIInfo(_vehicle, command)->getParamInfo(i, showUI);
546

547
            if (showUI && paramInfo && paramInfo->enumStrings().count() != 0) {
548 549 550 551 552 553 554 555
                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);
556
                _comboboxFacts.append(paramFact);
557 558 559
            }
        }
    }
560
}
561

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

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

577
        if (specifiesCoordinate() || specifiesAltitudeOnly()) {
578 579 580 581 582 583
            MAV_FRAME frame = _missionItem.frame();
            switch (frame) {
            case MAV_FRAME_GLOBAL:
            case MAV_FRAME_GLOBAL_RELATIVE_ALT:
                return true;

584 585
            case MAV_FRAME_GLOBAL_TERRAIN_ALT:
                return supportsTerrainFrame();
586 587 588
            default:
                return false;
            }
589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611
        }

        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)
{
612
    if (!_homePositionSpecialCase || (_dirty != dirty)) {
613
        _dirty = dirty;
614 615 616 617
        if (!dirty) {
            _cameraSection->setDirty(false);
            _speedSection->setDirty(false);
        }
618
        emit dirtyChanged(dirty);
619 620 621
    }
}

622
void SimpleMissionItem::_setDirty(void)
623
{
624 625 626
    if (!_ignoreDirtyChangeSignals) {
        setDirty(true);
    }
627 628 629 630 631 632 633
}

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

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

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

661
    emit coordinateHasRelativeAltitudeChanged(_altitudeMode == QGroundControlQmlGlobal::AltitudeModeRelative);
662 663
}

664
void SimpleMissionItem::_altitudeChanged(void)
665
{
666 667 668 669
    if (!specifiesAltitude()) {
        return;
    }

670
    if (_altitudeMode == QGroundControlQmlGlobal::AltitudeModeAboveTerrain) {
671
        _amslAltAboveTerrainFact.setRawValue(qQNaN());
672 673 674
        _terrainAltChanged();
    } else {
        _missionItem._param7Fact.setRawValue(_altitudeFact.rawValue());
675 676 677
    }
}

678 679
void SimpleMissionItem::_terrainAltChanged(void)
{
680
    if (!specifiesAltitude() || _altitudeMode != QGroundControlQmlGlobal::AltitudeModeAboveTerrain) {
681 682 683 684 685 686 687 688 689
        // 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 {
690 691 692 693 694 695
        double newAboveTerrain = terrainAltitude() + _altitudeFact.rawValue().toDouble();
        double oldAboveTerrain = _amslAltAboveTerrainFact.rawValue().toDouble();
        if (qIsNaN(oldAboveTerrain) || !qFuzzyCompare(newAboveTerrain, oldAboveTerrain)) {
            _missionItem._param7Fact.setRawValue(newAboveTerrain);
            _amslAltAboveTerrainFact.setRawValue(newAboveTerrain);
        }
696
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
697
    emit readyForSaveStateChanged();
698 699
}

DonLakeFlyer's avatar
DonLakeFlyer committed
700
SimpleMissionItem::ReadyForSaveState SimpleMissionItem::readyForSaveState(void) const
701
{
702 703 704 705
    if (_wizardMode) {
        return NotReadyForSaveData;
    }

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

710
void SimpleMissionItem::_setDefaultsForCommand(void)
711
{
712 713 714 715 716 717 718 719 720 721
    // 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);
722 723 724 725
    } 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());
726 727 728
    }

    // Set global defaults first, then if there are param defaults they will get reset
729
    _altitudeMode = QGroundControlQmlGlobal::AltitudeModeRelative;
DonLakeFlyer's avatar
DonLakeFlyer committed
730
    emit altitudeModeChanged();
731
    _amslAltAboveTerrainFact.setRawValue(qQNaN());
732 733 734 735 736 737 738 739
    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);
    }
740

741
    MAV_CMD command = static_cast<MAV_CMD>(this->command());
742 743 744
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, command);
    if (uiInfo) {
        for (int i=1; i<=7; i++) {
745 746
            bool showUI;
            const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
747 748 749 750
            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());
            }
751 752 753
        }
    }

754 755
    switch (command) {
    case MAV_CMD_NAV_WAYPOINT:
756 757 758
        // We default all acceptance radius to 0. This allows flight controller to be in control of
        // accept radius.
        _missionItem.setParam2(0);
759 760 761
        break;

    case MAV_CMD_NAV_LAND:
Don Gagne's avatar
Don Gagne committed
762
    case MAV_CMD_NAV_VTOL_LAND:
Don Gagne's avatar
Don Gagne committed
763
    case MAV_CMD_DO_SET_ROI_LOCATION:
DonLakeFlyer's avatar
DonLakeFlyer committed
764
        _altitudeFact.setRawValue(0);
765 766
        _missionItem.setParam7(0);
        break;
Donald Gagne's avatar
Donald Gagne committed
767 768
    default:
        break;
769 770 771
    }

    _missionItem.setAutoContinue(true);
772
    _missionItem.setFrame((specifiesCoordinate() || specifiesAltitudeOnly()) ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_MISSION);
773 774 775 776 777 778 779 780 781 782 783 784 785 786 787
    setRawEdit(false);
}

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

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

QString SimpleMissionItem::category(void) const
{
788
    return _commandTree->getUIInfo(_vehicle, static_cast<MAV_CMD>(command()))->category();
789 790
}

791
void SimpleMissionItem::setCommand(int command)
792
{
793 794
    if (static_cast<MAV_CMD>(command) != _missionItem.command()) {
        _missionItem.setCommand(static_cast<MAV_CMD>(command));
795
        _updateOptionalSections();
796 797 798 799 800
    }
}

void SimpleMissionItem::setCoordinate(const QGeoCoordinate& coordinate)
{
801 802 803 804
    // 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());
805 806
    }
}
807 808 809

void SimpleMissionItem::setSequenceNumber(int sequenceNumber)
{
810 811 812 813 814 815
    if (_missionItem.sequenceNumber() != sequenceNumber) {
        _missionItem.setSequenceNumber(sequenceNumber);
        emit sequenceNumberChanged(sequenceNumber);
        // This is too likely to ignore
        emit abbreviationChanged();
    }
816
}
817

DonLakeFlyer's avatar
DonLakeFlyer committed
818
double SimpleMissionItem::specifiedFlightSpeed(void)
819
{
820 821 822 823 824
    if (_speedSection->specifyFlightSpeed()) {
        return _speedSection->flightSpeed()->rawValue().toDouble();
    } else {
        return missionItem().specifiedFlightSpeed();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
825 826 827 828 829
}

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

832 833 834 835 836
double SimpleMissionItem::specifiedGimbalPitch(void)
{
    return _cameraSection->available() ? _cameraSection->specifiedGimbalPitch() : missionItem().specifiedGimbalPitch();
}

837
bool SimpleMissionItem::scanForSections(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle)
838
{
839
    bool sectionFound = false;
840

841
    Q_UNUSED(vehicle);
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 867 868
    // Add new sections

    _cameraSection = new CameraSection(_vehicle, this);
    _speedSection = new SpeedSection(_vehicle, 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());
DonLakeFlyer's avatar
DonLakeFlyer committed
921 922 923
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, command);

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