SimpleMissionItem.cc 39.6 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 56
SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, bool flyView, QObject* parent)
    : 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 72
    _setupMetaData();
    _connectSignals();
73
    _updateOptionalSections();
74

75
    _setDefaultsForCommand();
76
    _rebuildFacts();
77 78

    setDirty(false);
79 80
}

81 82
SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, bool flyView, const MissionItem& missionItem, QObject* parent)
    : VisualMissionItem         (masterController, flyView, parent)
83 84 85 86 87 88 89 90 91 92 93 94
    , _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)
95
{
Don Gagne's avatar
Don Gagne committed
96 97
    _editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml");

98
    struct MavFrame2AltMode_s {
99 100
        MAV_FRAME                               mavFrame;
        QGroundControlQmlGlobal::AltitudeMode   altMode;
101 102 103
    };

    const struct MavFrame2AltMode_s rgMavFrame2AltMode[] = {
104 105 106
        { MAV_FRAME_GLOBAL_TERRAIN_ALT,     QGroundControlQmlGlobal::AltitudeModeTerrainFrame },
        { MAV_FRAME_GLOBAL,                 QGroundControlQmlGlobal::AltitudeModeAbsolute },
        { MAV_FRAME_GLOBAL_RELATIVE_ALT,    QGroundControlQmlGlobal::AltitudeModeRelative },
107
    };
108
    _altitudeMode = QGroundControlQmlGlobal::AltitudeModeRelative;
109 110 111 112 113 114 115 116
    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;
        }
    }

117
    _isCurrentItem = missionItem.isCurrentItem();
118
    _altitudeFact.setRawValue(specifiesCoordinate() || specifiesAltitudeOnly() ? _missionItem._param7Fact.rawValue() : qQNaN());
119
    _amslAltAboveTerrainFact.setRawValue(qQNaN());
120

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

    // Signal coordinate changed to kick off terrain query
    emit coordinateChanged(coordinate());
133 134

    setDirty(false);
135 136
}

137 138 139
void SimpleMissionItem::_connectSignals(void)
{
    // Connect to change signals to track dirty state
140 141 142 143 144 145 146 147 148 149 150 151 152 153 154
    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);
155

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

160 161
    connect(this, &SimpleMissionItem::wizardModeChanged,             this, &SimpleMissionItem::readyForSaveStateChanged);

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

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

170 171 172 173 174 175
    // 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.
176
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::_setDefaultsForCommand);
177 178
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::commandNameChanged);
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::commandDescriptionChanged);
179
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::abbreviationChanged);
180
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::specifiesCoordinateChanged);
181
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::specifiesAltitudeOnlyChanged);
182 183 184
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::isStandaloneCoordinateChanged);

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

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

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

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

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

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

SimpleMissionItem::~SimpleMissionItem()
{    
}

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

    appendMissionItems(items, this);

    for (int i=0; i<items.count(); i++) {
        MissionItem* item = items[i];
        QJsonObject saveObject;
        item->save(saveObject);
261 262 263 264 265 266 267 268
        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();
            }
        }
269 270 271
        missionItems.append(saveObject);
        item->deleteLater();
    }
272 273 274 275
}

bool SimpleMissionItem::load(QTextStream &loadStream)
{
276 277
    bool success;
    if ((success = _missionItem.load(loadStream))) {
278
        if (specifiesCoordinate()) {
279
            _altitudeMode = _missionItem.relativeAltitude() ? QGroundControlQmlGlobal::AltitudeModeRelative : QGroundControlQmlGlobal::AltitudeModeAbsolute;
280 281 282
            _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue());
            _amslAltAboveTerrainFact.setRawValue(qQNaN());
        }
283 284
        _updateOptionalSections();
    }
285

286
    return success;
287 288
}

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

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

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

    _updateOptionalSections();

    return true;
319 320 321 322
}

bool SimpleMissionItem::isStandaloneCoordinate(void) const
{
323
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)command());
324 325
    if (uiInfo) {
        return uiInfo->isStandaloneCoordinate();
326 327 328 329 330 331 332
    } else {
        return false;
    }
}

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

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

351 352
QString SimpleMissionItem::commandDescription(void) const
{
353
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)command());
354 355
    if (uiInfo) {
        return uiInfo->description();
356 357 358 359 360 361 362 363
    } else {
        qWarning() << "Should not ask for command description on unknown command";
        return commandName();
    }
}

QString SimpleMissionItem::commandName(void) const
{
364
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, (MAV_CMD)command());
365 366
    if (uiInfo) {
        return uiInfo->friendlyName();
367 368
    } else {
        qWarning() << "Request for command name on unknown command";
369
        return tr("Unknown: %1").arg(command());
370 371 372
    }
}

373 374 375
QString SimpleMissionItem::abbreviation() const
{
    if (homePosition())
376
        return tr("L");
377 378

    switch(command()) {
379
    case MAV_CMD_NAV_TAKEOFF:
380
        return tr("Takeoff");
381
    case MAV_CMD_NAV_LAND:
382
        return tr("Land");
383
    case MAV_CMD_NAV_VTOL_TAKEOFF:
384
        return tr("VTOL Takeoff");
385
    case MAV_CMD_NAV_VTOL_LAND:
386
        return tr("VTOL Land");
387
    case MAV_CMD_DO_SET_ROI:
388
    case MAV_CMD_DO_SET_ROI_LOCATION:
389 390 391
        return tr("ROI");
    default:
        return QString();
392 393 394
    }
}

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

424 425 426 427 428 429 430 431 432 433
        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 };

434
        const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command);
435

436
        for (int i=1; i<=7; i++) {
437 438
            bool showUI;
            const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
439

440
            if (showUI && paramInfo && paramInfo->enumStrings().count() == 0 && !paramInfo->nanUnchanged()) {
441 442 443 444 445 446 447
                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);
448
                _textFieldFacts.append(paramFact);
449 450 451
            }
        }

452
        _ignoreDirtyChangeSignals = false;
453 454 455
    }
}

456
void SimpleMissionItem::_rebuildNaNFacts(void)
457
{
458 459 460 461 462 463 464 465 466 467 468 469 470 471 472
    _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 };

473
        const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command);
474 475

        for (int i=1; i<=7; i++) {
476 477
            bool showUI;
            const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
478

479
            if (showUI && paramInfo && paramInfo->nanUnchanged()) {
480
                // 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
481
                // and not _controllerVehicle which is always offline.
482 483
                Vehicle* firmwareVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
                if (!firmwareVehicle) {
484
                    firmwareVehicle = _controllerVehicle;
485
                }
486
                bool hideWaypointHeading = (command == MAV_CMD_NAV_WAYPOINT || command == MAV_CMD_NAV_TAKEOFF) && (i == 4) && firmwareVehicle->firmwarePlugin()->vehicleYawsToNextWaypointInMission(firmwareVehicle);
487 488 489
                if (hideWaypointHeading) {
                    continue;
                }
490

491 492 493 494 495 496 497 498 499 500 501 502 503 504 505
                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;
    }
}

506
bool SimpleMissionItem::specifiesAltitude(void) const
507
{
508
    return specifiesCoordinate() || specifiesAltitudeOnly();
509 510
}

511
void SimpleMissionItem::_rebuildComboBoxFacts(void)
512
{
513
    _comboboxFacts.clear();
514 515

    if (rawEdit()) {
516 517
        _comboboxFacts.append(&_missionItem._commandFact);
        _comboboxFacts.append(&_missionItem._frameFact);
518 519 520 521 522 523 524 525 526 527 528 529
    } 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++) {
530
            bool showUI;
531
            const MissionCmdParamInfo* paramInfo = _commandTree->getUIInfo(_controllerVehicle, command)->getParamInfo(i, showUI);
532

533
            if (showUI && paramInfo && paramInfo->enumStrings().count() != 0) {
534 535 536 537 538 539 540 541
                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);
542
                _comboboxFacts.append(paramFact);
543 544 545
            }
        }
    }
546
}
547

548 549 550 551 552
void SimpleMissionItem::_rebuildFacts(void)
{
    _rebuildTextFieldFacts();
    _rebuildNaNFacts();
    _rebuildComboBoxFacts();
553 554 555 556
}

bool SimpleMissionItem::friendlyEditAllowed(void) const
{
557
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, static_cast<MAV_CMD>(command()));
558
    if (uiInfo && uiInfo->friendlyEdit()) {
559 560 561 562
        if (!_missionItem.autoContinue()) {
            return false;
        }

563
        if (specifiesCoordinate() || specifiesAltitudeOnly()) {
564 565 566 567
            MAV_FRAME frame = _missionItem.frame();
            switch (frame) {
            case MAV_FRAME_GLOBAL:
            case MAV_FRAME_GLOBAL_RELATIVE_ALT:
568
            case MAV_FRAME_GLOBAL_TERRAIN_ALT:
569
                return true;
570 571 572
            default:
                return false;
            }
573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595
        }

        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)
{
596
    if (!_homePositionSpecialCase || (_dirty != dirty)) {
597
        _dirty = dirty;
598 599 600 601
        if (!dirty) {
            _cameraSection->setDirty(false);
            _speedSection->setDirty(false);
        }
602
        emit dirtyChanged(dirty);
603 604 605
    }
}

606
void SimpleMissionItem::_setDirty(void)
607
{
608 609 610
    if (!_ignoreDirtyChangeSignals) {
        setDirty(true);
    }
611 612 613 614 615 616 617
}

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

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

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

645
    emit coordinateHasRelativeAltitudeChanged(_altitudeMode == QGroundControlQmlGlobal::AltitudeModeRelative);
646 647
}

648
void SimpleMissionItem::_altitudeChanged(void)
649
{
650 651 652 653
    if (!specifiesAltitude()) {
        return;
    }

654
    if (_altitudeMode == QGroundControlQmlGlobal::AltitudeModeAboveTerrain) {
655
        _amslAltAboveTerrainFact.setRawValue(qQNaN());
656 657 658
        _terrainAltChanged();
    } else {
        _missionItem._param7Fact.setRawValue(_altitudeFact.rawValue());
659 660 661
    }
}

662 663
void SimpleMissionItem::_terrainAltChanged(void)
{
664
    if (!specifiesAltitude() || _altitudeMode != QGroundControlQmlGlobal::AltitudeModeAboveTerrain) {
665 666 667 668 669 670 671 672 673
        // 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 {
674 675 676 677 678 679
        double newAboveTerrain = terrainAltitude() + _altitudeFact.rawValue().toDouble();
        double oldAboveTerrain = _amslAltAboveTerrainFact.rawValue().toDouble();
        if (qIsNaN(oldAboveTerrain) || !qFuzzyCompare(newAboveTerrain, oldAboveTerrain)) {
            _missionItem._param7Fact.setRawValue(newAboveTerrain);
            _amslAltAboveTerrainFact.setRawValue(newAboveTerrain);
        }
680
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
681
    emit readyForSaveStateChanged();
682 683
}

DonLakeFlyer's avatar
DonLakeFlyer committed
684
SimpleMissionItem::ReadyForSaveState SimpleMissionItem::readyForSaveState(void) const
685
{
686 687 688 689
    if (_wizardMode) {
        return NotReadyForSaveData;
    }

DonLakeFlyer's avatar
DonLakeFlyer committed
690 691
    bool terrainReady =  !specifiesAltitude() || !qIsNaN(_missionItem._param7Fact.rawValue().toDouble());
    return terrainReady ? ReadyForSave : NotReadyForSaveTerrain;
692 693
}

694
void SimpleMissionItem::_setDefaultsForCommand(void)
695
{
696 697 698 699 700 701 702 703 704 705
    // 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);
706 707 708 709
    } 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());
710 711 712
    }

    // Set global defaults first, then if there are param defaults they will get reset
713
    _altitudeMode = QGroundControlQmlGlobal::AltitudeModeRelative;
DonLakeFlyer's avatar
DonLakeFlyer committed
714
    emit altitudeModeChanged();
715
    _amslAltAboveTerrainFact.setRawValue(qQNaN());
716 717 718 719 720 721 722 723
    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);
    }
724

725
    MAV_CMD command = static_cast<MAV_CMD>(this->command());
726
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command);
727 728
    if (uiInfo) {
        for (int i=1; i<=7; i++) {
729 730
            bool showUI;
            const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
731 732 733 734
            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());
            }
735 736 737
        }
    }

738 739
    switch (command) {
    case MAV_CMD_NAV_WAYPOINT:
740 741 742
        // We default all acceptance radius to 0. This allows flight controller to be in control of
        // accept radius.
        _missionItem.setParam2(0);
743 744 745
        break;

    case MAV_CMD_NAV_LAND:
Don Gagne's avatar
Don Gagne committed
746
    case MAV_CMD_NAV_VTOL_LAND:
Don Gagne's avatar
Don Gagne committed
747
    case MAV_CMD_DO_SET_ROI_LOCATION:
DonLakeFlyer's avatar
DonLakeFlyer committed
748
        _altitudeFact.setRawValue(0);
749 750
        _missionItem.setParam7(0);
        break;
Donald Gagne's avatar
Donald Gagne committed
751 752
    default:
        break;
753 754 755
    }

    _missionItem.setAutoContinue(true);
756
    _missionItem.setFrame((specifiesCoordinate() || specifiesAltitudeOnly()) ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_MISSION);
757 758 759 760 761 762 763 764 765 766 767 768 769 770 771
    setRawEdit(false);
}

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

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

QString SimpleMissionItem::category(void) const
{
772
    return _commandTree->getUIInfo(_controllerVehicle, static_cast<MAV_CMD>(command()))->category();
773 774
}

775
void SimpleMissionItem::setCommand(int command)
776
{
777 778
    if (static_cast<MAV_CMD>(command) != _missionItem.command()) {
        _missionItem.setCommand(static_cast<MAV_CMD>(command));
779
        _updateOptionalSections();
780 781 782 783 784
    }
}

void SimpleMissionItem::setCoordinate(const QGeoCoordinate& coordinate)
{
785 786 787 788
    // 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());
789 790
    }
}
791 792 793

void SimpleMissionItem::setSequenceNumber(int sequenceNumber)
{
794 795 796 797 798 799
    if (_missionItem.sequenceNumber() != sequenceNumber) {
        _missionItem.setSequenceNumber(sequenceNumber);
        emit sequenceNumberChanged(sequenceNumber);
        // This is too likely to ignore
        emit abbreviationChanged();
    }
800
}
801

DonLakeFlyer's avatar
DonLakeFlyer committed
802
double SimpleMissionItem::specifiedFlightSpeed(void)
803
{
804 805 806 807 808
    if (_speedSection->specifyFlightSpeed()) {
        return _speedSection->flightSpeed()->rawValue().toDouble();
    } else {
        return missionItem().specifiedFlightSpeed();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
809 810 811 812 813
}

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

816 817 818 819 820
double SimpleMissionItem::specifiedGimbalPitch(void)
{
    return _cameraSection->available() ? _cameraSection->specifiedGimbalPitch() : missionItem().specifiedGimbalPitch();
}

821 822 823 824 825 826 827 828 829 830 831 832
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();
    }
}

833
bool SimpleMissionItem::scanForSections(QmlObjectListModel* visualItems, int scanIndex, PlanMasterController* /*masterController*/)
834
{
835
    bool sectionFound = false;
836 837

    if (_cameraSection->available()) {
838 839 840 841
        sectionFound |= _cameraSection->scanForSection(visualItems, scanIndex);
    }
    if (_speedSection->available()) {
        sectionFound |= _speedSection->scanForSection(visualItems, scanIndex);
842
    }
843 844

    return sectionFound;
845 846
}

847
void SimpleMissionItem::_updateOptionalSections(void)
848
{
849
    // Remove previous sections
850 851
    if (_cameraSection) {
        _cameraSection->deleteLater();
852
        _cameraSection = nullptr;
853
    }
854 855
    if (_speedSection) {
        _speedSection->deleteLater();
856
        _speedSection = nullptr;
857
    }
858

859 860
    // Add new sections

861 862
    _cameraSection = new CameraSection(_masterController, this);
    _speedSection = new SpeedSection(_masterController, this);
863
    if (static_cast<MAV_CMD>(command()) == MAV_CMD_NAV_WAYPOINT) {
864
        _cameraSection->setAvailable(true);
865
        _speedSection->setAvailable(true);
866 867
    }

868 869 870 871 872 873
    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);
874

875 876 877
    connect(_speedSection,  &SpeedSection::dirtyChanged,                this, &SimpleMissionItem::_sectionDirtyChanged);
    connect(_speedSection,  &SpeedSection::itemCountChanged,            this, &SimpleMissionItem::_updateLastSequenceNumber);
    connect(_speedSection,  &SpeedSection::specifiedFlightSpeedChanged, this, &SimpleMissionItem::specifiedFlightSpeedChanged);
878

879
    emit cameraSectionChanged(_cameraSection);
880
    emit speedSectionChanged(_speedSection);
881
    emit lastSequenceNumberChanged(lastSequenceNumber());
882 883 884 885
}

int SimpleMissionItem::lastSequenceNumber(void) const
{
886
    return sequenceNumber() + (_cameraSection ? _cameraSection->itemCount() : 0) + (_speedSection ? _speedSection->itemCount() : 0);
887 888 889 890 891 892 893
}

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

894
void SimpleMissionItem::_sectionDirtyChanged(bool dirty)
895 896 897 898 899 900 901 902 903 904 905 906 907
{
    if (dirty) {
        setDirty(true);
    }
}

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

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

908 909
    _cameraSection->appendSectionItems(items, missionItemParent, seqNum);
    _speedSection->appendSectionItems(items, missionItemParent, seqNum);
910
}
DonLakeFlyer's avatar
DonLakeFlyer committed
911 912 913

void SimpleMissionItem::applyNewAltitude(double newAltitude)
{
914
    MAV_CMD command = static_cast<MAV_CMD>(this->command());
915
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, command);
DonLakeFlyer's avatar
DonLakeFlyer committed
916 917

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

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

947
void SimpleMissionItem::setAltitudeMode(QGroundControlQmlGlobal::AltitudeMode altitudeMode)
948 949 950 951 952 953
{
    if (altitudeMode != _altitudeMode) {
        _altitudeMode = altitudeMode;
        emit altitudeModeChanged();
    }
}
954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978

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