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


11 12 13
#include <QStringList>
#include <QDebug>

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

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

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

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

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

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

71
    _setupMetaData();
72

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

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

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

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

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

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

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

    setDirty(false);
137 138
}

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

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

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

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

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

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

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

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

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

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

    // The following changes must signal currentVTOLModeChanged to cause a MissionController recalc
    connect(this,                               &SimpleMissionItem::commandChanged,         this, &SimpleMissionItem::_signalIfVTOLTransitionCommand);
    connect(&_missionItem._param1Fact,          &Fact::valueChanged,                        this, &SimpleMissionItem::_signalIfVTOLTransitionCommand);
199 200

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

203
    // Propogate signals from MissionItem up to SimpleMissionItem
204 205
    connect(&_missionItem,                      &MissionItem::sequenceNumberChanged,        this, &SimpleMissionItem::sequenceNumberChanged);
    connect(&_missionItem,                      &MissionItem::specifiedFlightSpeedChanged,  this, &SimpleMissionItem::specifiedFlightSpeedChanged);
206 207 208 209 210 211 212 213 214
}

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

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

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

SimpleMissionItem::~SimpleMissionItem()
{    
}

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

    appendMissionItems(items, this);

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

bool SimpleMissionItem::load(QTextStream &loadStream)
{
288 289
    bool success;
    if ((success = _missionItem.load(loadStream))) {
290
        if (specifiesAltitude()) {
291
            _altitudeMode = _missionItem.relativeAltitude() ? QGroundControlQmlGlobal::AltitudeModeRelative : QGroundControlQmlGlobal::AltitudeModeAbsolute;
292 293 294
            _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue());
            _amslAltAboveTerrainFact.setRawValue(qQNaN());
        }
295
        _connectSignals();
296
        _updateOptionalSections();
297 298
        _rebuildFacts();
        setDirty(false);
299
    }
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
    if (specifiesAltitude()) {
311 312 313 314 315 316 317 318 319 320
        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
            _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue());
            _amslAltAboveTerrainFact.setRawValue(qQNaN());
        }
    }

331
    _connectSignals();
332
    _updateOptionalSections();
333 334
    _rebuildFacts();
    setDirty(false);
335 336

    return true;
337 338 339 340
}

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

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

359 360
bool SimpleMissionItem::specifiesAltitudeOnly(void) const
{
361
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, (MAV_CMD)command());
362 363 364 365 366 367 368
    if (uiInfo) {
        return uiInfo->specifiesAltitudeOnly();
    } else {
        return false;
    }
}

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

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

391 392 393
QString SimpleMissionItem::abbreviation() const
{
    if (homePosition())
394
        return tr("L");
395 396

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

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

442 443 444 445 446 447 448 449 450 451
        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 };

452
        const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command);
453

454 455 456 457 458 459 460 461 462 463 464 465 466 467 468
        if (uiInfo) {
            for (int i=1; i<=7; i++) {
                bool showUI;
                const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);

                if (showUI && paramInfo && paramInfo->enumStrings().count() == 0 && !paramInfo->nanUnchanged()) {
                    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);
                    _textFieldFacts.append(paramFact);
                }
469 470 471
            }
        }

472
        _ignoreDirtyChangeSignals = false;
473 474 475
    }
}

476
void SimpleMissionItem::_rebuildNaNFacts(void)
477
{
478 479 480 481 482 483 484 485 486 487 488 489 490 491 492
    _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 };

493
        const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command);
494

495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515
        if (uiInfo) {
            for (int i=1; i<=7; i++) {
                bool showUI;
                const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);

                if (showUI && paramInfo && paramInfo->nanUnchanged()) {
                    // 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 _controllerVehicle which is always offline.
                    Vehicle* firmwareVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle();
                    if (!firmwareVehicle) {
                        firmwareVehicle = _controllerVehicle;
                    }

                    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);
516
                }
517 518 519 520 521 522 523
            }
        }

        _ignoreDirtyChangeSignals = false;
    }
}

524
bool SimpleMissionItem::specifiesAltitude(void) const
525
{
526
    return specifiesCoordinate() || specifiesAltitudeOnly();
527 528
}

529
void SimpleMissionItem::_rebuildComboBoxFacts(void)
530
{
531
    _comboboxFacts.clear();
532 533

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

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

566 567 568 569 570
void SimpleMissionItem::_rebuildFacts(void)
{
    _rebuildTextFieldFacts();
    _rebuildNaNFacts();
    _rebuildComboBoxFacts();
571 572 573 574
}

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

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

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

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

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

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

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

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

670
    if (_altitudeMode == QGroundControlQmlGlobal::AltitudeModeAboveTerrain || _altitudeMode == QGroundControlQmlGlobal::AltitudeModeTerrainFrame) {
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()) {
681 682 683 684
        // We don't need terrain data
        return;
    }

685 686 687 688 689 690 691 692
    if (_altitudeMode == QGroundControlQmlGlobal::AltitudeModeAboveTerrain) {
        if (qIsNaN(terrainAltitude())) {
            // Set NaNs to signal we are waiting on terrain data
            _missionItem._param7Fact.setRawValue(qQNaN());
            _amslAltAboveTerrainFact.setRawValue(qQNaN());
        } else {
            double newAboveTerrain = terrainAltitude() + _altitudeFact.rawValue().toDouble();
            double oldAboveTerrain = _amslAltAboveTerrainFact.rawValue().toDouble();
693
            if (!QGC::fuzzyCompare(newAboveTerrain, oldAboveTerrain)) {
694 695 696
                _missionItem._param7Fact.setRawValue(newAboveTerrain);
                _amslAltAboveTerrainFact.setRawValue(newAboveTerrain);
            }
697
        }
698 699
        emit readyForSaveStateChanged();
    }
700 701
}

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

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

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

    // Set global defaults first, then if there are param defaults they will get reset
731
    _altitudeMode = QGroundControlQmlGlobal::AltitudeModeRelative;
DonLakeFlyer's avatar
DonLakeFlyer committed
732
    emit altitudeModeChanged();
733
    _amslAltAboveTerrainFact.setRawValue(qQNaN());
734
    if (specifiesAltitude()) {
735 736 737
        double defaultAlt = qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue().toDouble();
        _altitudeFact.setRawValue(defaultAlt);
        _missionItem._param7Fact.setRawValue(defaultAlt);
738 739 740
        // Note that setAltitudeMode will also set MAV_FRAME correctly through signalling
        // Takeoff items always use relative alt since that is the highest quality data to base altitude from
        setAltitudeMode(isTakeoffItem() ? QGroundControlQmlGlobal::AltitudeModeRelative : _missionController->globalAltitudeModeDefault());
741 742 743
    } else {
        _altitudeFact.setRawValue(0);
        _missionItem._param7Fact.setRawValue(0);
744
        _missionItem.setFrame(MAV_FRAME_MISSION);
745
    }
746

747
    MAV_CMD command = static_cast<MAV_CMD>(this->command());
748
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command);
749 750
    if (uiInfo) {
        for (int i=1; i<=7; i++) {
751 752
            bool showUI;
            const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
753 754 755 756
            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());
            }
757 758 759
        }
    }

760
    if (command == MAV_CMD_NAV_WAYPOINT) {
761 762 763
        // We default all acceptance radius to 0. This allows flight controller to be in control of
        // accept radius.
        _missionItem.setParam2(0);
764
    } else if ((uiInfo && uiInfo->isLandCommand()) || command == MAV_CMD_DO_SET_ROI_LOCATION) {
DonLakeFlyer's avatar
DonLakeFlyer committed
765
        _altitudeFact.setRawValue(0);
766
        _missionItem.setParam7(0);
767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784
    }

    _missionItem.setAutoContinue(true);
    setRawEdit(false);
}

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

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

QString SimpleMissionItem::category(void) const
{
785 786
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, static_cast<MAV_CMD>(command()));
    return uiInfo ? uiInfo->category() : QString();
787 788
}

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

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

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

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

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

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

835 836 837 838 839 840 841 842 843 844 845 846
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();
    }
}

847
bool SimpleMissionItem::scanForSections(QmlObjectListModel* visualItems, int scanIndex, PlanMasterController* /*masterController*/)
848
{
849
    bool sectionFound = false;
850 851

    if (_cameraSection->available()) {
852 853 854 855
        sectionFound |= _cameraSection->scanForSection(visualItems, scanIndex);
    }
    if (_speedSection->available()) {
        sectionFound |= _speedSection->scanForSection(visualItems, scanIndex);
856
    }
857 858

    return sectionFound;
859 860
}

861
void SimpleMissionItem::_updateOptionalSections(void)
862
{
863
    // Remove previous sections
864 865
    if (_cameraSection) {
        _cameraSection->deleteLater();
866
        _cameraSection = nullptr;
867
    }
868 869
    if (_speedSection) {
        _speedSection->deleteLater();
870
        _speedSection = nullptr;
871
    }
872

873 874
    // Add new sections

875 876
    _cameraSection = new CameraSection(_masterController, this);
    _speedSection = new SpeedSection(_masterController, this);
877
    if (static_cast<MAV_CMD>(command()) == MAV_CMD_NAV_WAYPOINT) {
878
        _cameraSection->setAvailable(true);
879
        _speedSection->setAvailable(true);
880 881
    }

882 883 884 885 886 887
    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);
888

889 890 891
    connect(_speedSection,  &SpeedSection::dirtyChanged,                this, &SimpleMissionItem::_sectionDirtyChanged);
    connect(_speedSection,  &SpeedSection::itemCountChanged,            this, &SimpleMissionItem::_updateLastSequenceNumber);
    connect(_speedSection,  &SpeedSection::specifiedFlightSpeedChanged, this, &SimpleMissionItem::specifiedFlightSpeedChanged);
892

893
    emit cameraSectionChanged(_cameraSection);
894
    emit speedSectionChanged(_speedSection);
895
    emit lastSequenceNumberChanged(lastSequenceNumber());
896 897 898 899
}

int SimpleMissionItem::lastSequenceNumber(void) const
{
900
    return sequenceNumber() + (_cameraSection ? _cameraSection->itemCount() : 0) + (_speedSection ? _speedSection->itemCount() : 0);
901 902 903 904 905 906 907
}

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

908
void SimpleMissionItem::_sectionDirtyChanged(bool dirty)
909 910 911 912 913 914 915 916 917 918 919 920 921
{
    if (dirty) {
        setDirty(true);
    }
}

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

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

922 923
    _cameraSection->appendSectionItems(items, missionItemParent, seqNum);
    _speedSection->appendSectionItems(items, missionItemParent, seqNum);
924
}
DonLakeFlyer's avatar
DonLakeFlyer committed
925 926 927

void SimpleMissionItem::applyNewAltitude(double newAltitude)
{
928
    MAV_CMD command = static_cast<MAV_CMD>(this->command());
929
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command);
DonLakeFlyer's avatar
DonLakeFlyer committed
930

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

void SimpleMissionItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus)
{
    VisualMissionItem::setMissionFlightStatus(missionFlightStatus);
947 948

    // If speed and/or gimbal are not specifically set on this item. Then use the flight status values as initial defaults should a user turn them on.
949
    if (_speedSection->available() && !_speedSection->specifyFlightSpeed() && !QGC::fuzzyCompare(_speedSection->flightSpeed()->rawValue().toDouble(), missionFlightStatus.vehicleSpeed)) {
950 951 952
        _speedSection->flightSpeed()->setRawValue(missionFlightStatus.vehicleSpeed);
    }
    if (_cameraSection->available() && !_cameraSection->specifyGimbal()) {
953
        if (!qIsNaN(missionFlightStatus.gimbalYaw) && !QGC::fuzzyCompare(_cameraSection->gimbalYaw()->rawValue().toDouble(), missionFlightStatus.gimbalYaw)) {
954 955
            _cameraSection->gimbalYaw()->setRawValue(missionFlightStatus.gimbalYaw);
        }
956
        if (!qIsNaN(missionFlightStatus.gimbalPitch) && !QGC::fuzzyCompare(_cameraSection->gimbalPitch()->rawValue().toDouble(), missionFlightStatus.gimbalPitch)) {
957 958 959 960
            _cameraSection->gimbalPitch()->setRawValue(missionFlightStatus.gimbalPitch);
        }
    }
}
961

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

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;
}
994 995 996

bool SimpleMissionItem::isLandCommand(void) const
{
997
    return _commandTree->isLandCommand(static_cast<MAV_CMD>(this->command()));
998
}
999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012

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

double SimpleMissionItem::amslEntryAlt(void) const
{
    switch (_altitudeMode) {
    case QGroundControlQmlGlobal::AltitudeModeTerrainFrame:
1013
        return _missionItem.param7() + _terrainAltitude;
1014 1015 1016 1017 1018
    case QGroundControlQmlGlobal::AltitudeModeAboveTerrain:
    case QGroundControlQmlGlobal::AltitudeModeAbsolute:
        return _missionItem.param7();
    case QGroundControlQmlGlobal::AltitudeModeRelative:
        return _missionItem.param7() + _masterController->missionController()->plannedHomePosition().altitude();
1019 1020 1021
    case QGroundControlQmlGlobal::AltitudeModeNone:
        qWarning() << "Internal Error SimpleMissionItem::amslEntryAlt: Invalid altitudeMode:AltitudeModeNone";
        return qQNaN();
1022
    }
1023 1024 1025

    qWarning() << "Internal Error SimpleMissionItem::amslEntryAlt: Invalid altitudeMode:" << _altitudeMode;
    return qQNaN();
1026
}
1027 1028 1029 1030 1031 1032 1033 1034

void SimpleMissionItem::_signalIfVTOLTransitionCommand(void)
{
    if (mavCommand() == MAV_CMD_DO_VTOL_TRANSITION) {
        // This will cause a MissionController recalc
        emit currentVTOLModeChanged();
    }
}