SimpleMissionItem.cc 40.1 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

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
    connect(&_missionItem._param1Fact,  &Fact::valueChanged, this, &SimpleMissionItem::_possibleAdditionalTimeDelayChanged);
180
    connect(&_missionItem._param4Fact,  &Fact::valueChanged, this, &SimpleMissionItem::_possibleVehicleYawChanged);
181

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

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

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

203 204 205 206 207 208
    // 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);
209 210 211 212 213 214 215 216 217
}

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

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

        enumStrings.clear();
        enumValues.clear();
224
        MissionCommandTree* commandTree = qgcApp()->toolbox()->missionCommandTree();
225
        for (const MAV_CMD command: commandTree->allCommandIds()) {
226 227
            enumStrings.append(commandTree->rawName(command));
            enumValues.append(QVariant((int)command));
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 257
        }
        _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);
258
    _altitudeFact.setMetaData(_altitudeMetaData);
259
    _amslAltAboveTerrainFact.setMetaData(_altitudeMetaData);
260 261 262 263 264 265
}

SimpleMissionItem::~SimpleMissionItem()
{    
}

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

    appendMissionItems(items, this);

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

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

301
    return success;
302 303
}

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

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

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

    _updateOptionalSections();

    return true;
334 335 336 337
}

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

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

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

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

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

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

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

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

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

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

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

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

467
        _ignoreDirtyChangeSignals = false;
468 469 470
    }
}

471
void SimpleMissionItem::_rebuildNaNFacts(void)
472
{
473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490
    _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++) {
491 492
            bool showUI;
            const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
493

494
            if (showUI && paramInfo && paramInfo->nanUnchanged()) {
495 496 497 498 499 500
                // 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;
                }
501
                bool hideWaypointHeading = (command == MAV_CMD_NAV_WAYPOINT || command == MAV_CMD_NAV_TAKEOFF) && (i == 4) && firmwareVehicle->firmwarePlugin()->vehicleYawsToNextWaypointInMission(firmwareVehicle);
502 503 504
                if (hideWaypointHeading) {
                    continue;
                }
505

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

838 839 840 841 842 843 844 845 846 847 848 849
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();
    }
}

850
bool SimpleMissionItem::scanForSections(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle)
851
{
852
    bool sectionFound = false;
853

854
    Q_UNUSED(vehicle);
855 856

    if (_cameraSection->available()) {
857 858 859 860
        sectionFound |= _cameraSection->scanForSection(visualItems, scanIndex);
    }
    if (_speedSection->available()) {
        sectionFound |= _speedSection->scanForSection(visualItems, scanIndex);
861
    }
862 863

    return sectionFound;
864 865
}

866
void SimpleMissionItem::_updateOptionalSections(void)
867
{
868
    // Remove previous sections
869 870
    if (_cameraSection) {
        _cameraSection->deleteLater();
871
        _cameraSection = nullptr;
872
    }
873 874
    if (_speedSection) {
        _speedSection->deleteLater();
875
        _speedSection = nullptr;
876
    }
877

878 879 880 881
    // Add new sections

    _cameraSection = new CameraSection(_vehicle, this);
    _speedSection = new SpeedSection(_vehicle, this);
882
    if (static_cast<MAV_CMD>(command()) == MAV_CMD_NAV_WAYPOINT) {
883
        _cameraSection->setAvailable(true);
884
        _speedSection->setAvailable(true);
885 886
    }

887 888 889 890 891 892
    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);
893

894 895 896
    connect(_speedSection,  &SpeedSection::dirtyChanged,                this, &SimpleMissionItem::_sectionDirtyChanged);
    connect(_speedSection,  &SpeedSection::itemCountChanged,            this, &SimpleMissionItem::_updateLastSequenceNumber);
    connect(_speedSection,  &SpeedSection::specifiedFlightSpeedChanged, this, &SimpleMissionItem::specifiedFlightSpeedChanged);
897

898
    emit cameraSectionChanged(_cameraSection);
899
    emit speedSectionChanged(_speedSection);
900
    emit lastSequenceNumberChanged(lastSequenceNumber());
901 902 903 904
}

int SimpleMissionItem::lastSequenceNumber(void) const
{
905
    return sequenceNumber() + (_cameraSection ? _cameraSection->itemCount() : 0) + (_speedSection ? _speedSection->itemCount() : 0);
906 907 908 909 910 911 912
}

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

913
void SimpleMissionItem::_sectionDirtyChanged(bool dirty)
914 915 916 917 918 919 920 921 922 923 924 925 926
{
    if (dirty) {
        setDirty(true);
    }
}

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

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

927 928
    _cameraSection->appendSectionItems(items, missionItemParent, seqNum);
    _speedSection->appendSectionItems(items, missionItemParent, seqNum);
929
}
DonLakeFlyer's avatar
DonLakeFlyer committed
930 931 932

void SimpleMissionItem::applyNewAltitude(double newAltitude)
{
933
    MAV_CMD command = static_cast<MAV_CMD>(this->command());
DonLakeFlyer's avatar
DonLakeFlyer committed
934 935 936
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, command);

    if (uiInfo->specifiesCoordinate() || uiInfo->specifiesAltitudeOnly()) {
937
        switch (static_cast<MAV_CMD>(this->command())) {
DonLakeFlyer's avatar
DonLakeFlyer committed
938 939 940 941 942
        case MAV_CMD_NAV_LAND:
        case MAV_CMD_NAV_VTOL_LAND:
            // Leave alone
            break;
        default:
943
            _altitudeFact.setRawValue(newAltitude);
DonLakeFlyer's avatar
DonLakeFlyer committed
944 945 946 947
            break;
        }
    }
}
948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964

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

966
void SimpleMissionItem::setAltitudeMode(QGroundControlQmlGlobal::AltitudeMode altitudeMode)
967 968 969 970 971 972
{
    if (altitudeMode != _altitudeMode) {
        _altitudeMode = altitudeMode;
        emit altitudeModeChanged();
    }
}
973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997

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