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


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

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

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

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

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

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

54 55
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* parent)
    : VisualMissionItem                 (vehicle, flyView, parent)
56 57 58
    , _rawEdit                          (false)
    , _dirty                            (false)
    , _ignoreDirtyChangeSignals         (false)
59 60
    , _speedSection                     (nullptr)
    , _cameraSection                    (nullptr)
61 62
    , _commandTree                      (qgcApp()->toolbox()->missionCommandTree())
    , _supportedCommandFact             (0, "Command:",             FactMetaData::valueTypeUint32)
63
    , _altitudeMode                     (QGroundControlQmlGlobal::AltitudeModeRelative)
64 65 66 67 68 69 70 71 72 73
    , _altitudeFact                     (0, "Altitude",             FactMetaData::valueTypeDouble)
    , _amslAltAboveTerrainFact          (0, "Alt above terrain",    FactMetaData::valueTypeDouble)
    , _param1MetaData                   (FactMetaData::valueTypeDouble)
    , _param2MetaData                   (FactMetaData::valueTypeDouble)
    , _param3MetaData                   (FactMetaData::valueTypeDouble)
    , _param4MetaData                   (FactMetaData::valueTypeDouble)
    , _param5MetaData                   (FactMetaData::valueTypeDouble)
    , _param6MetaData                   (FactMetaData::valueTypeDouble)
    , _param7MetaData                   (FactMetaData::valueTypeDouble)
    , _syncingHeadingDegreesAndParam4   (false)
74
{
Don Gagne's avatar
Don Gagne committed
75
    _editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml");
76

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

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

    setDirty(false);
85 86
}

87 88
SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, const MissionItem& missionItem, QObject* parent)
    : VisualMissionItem         (vehicle, flyView, parent)
89 90 91 92
    , _missionItem              (missionItem)
    , _rawEdit                  (false)
    , _dirty                    (false)
    , _ignoreDirtyChangeSignals (false)
93 94
    , _speedSection             (nullptr)
    , _cameraSection            (nullptr)
95 96 97 98 99 100 101 102 103 104 105
    , _commandTree              (qgcApp()->toolbox()->missionCommandTree())
    , _supportedCommandFact     (0,         "Command:",             FactMetaData::valueTypeUint32)
    , _altitudeFact             (0,         "Altitude",             FactMetaData::valueTypeDouble)
    , _amslAltAboveTerrainFact  (0,         "Alt above terrain",    FactMetaData::valueTypeDouble)
    , _param1MetaData           (FactMetaData::valueTypeDouble)
    , _param2MetaData           (FactMetaData::valueTypeDouble)
    , _param3MetaData           (FactMetaData::valueTypeDouble)
    , _param4MetaData           (FactMetaData::valueTypeDouble)
    , _param5MetaData           (FactMetaData::valueTypeDouble)
    , _param6MetaData           (FactMetaData::valueTypeDouble)
    , _param7MetaData           (FactMetaData::valueTypeDouble)
106
    , _syncingHeadingDegreesAndParam4           (false)
107
{
Don Gagne's avatar
Don Gagne committed
108 109
    _editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml");

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

    const struct MavFrame2AltMode_s rgMavFrame2AltMode[] = {
116 117 118
        { MAV_FRAME_GLOBAL_TERRAIN_ALT,     QGroundControlQmlGlobal::AltitudeModeTerrainFrame },
        { MAV_FRAME_GLOBAL,                 QGroundControlQmlGlobal::AltitudeModeAbsolute },
        { MAV_FRAME_GLOBAL_RELATIVE_ALT,    QGroundControlQmlGlobal::AltitudeModeRelative },
119
    };
120
    _altitudeMode = QGroundControlQmlGlobal::AltitudeModeRelative;
121 122 123 124 125 126 127 128
    for (size_t i=0; i<sizeof(rgMavFrame2AltMode)/sizeof(rgMavFrame2AltMode[0]); i++) {
        const MavFrame2AltMode_s& pMavFrame2AltMode = rgMavFrame2AltMode[i];
        if (pMavFrame2AltMode.mavFrame == missionItem.frame()) {
            _altitudeMode = pMavFrame2AltMode.altMode;
            break;
        }
    }

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

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

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

    setDirty(false);
147 148
}

149 150
SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent)
    : VisualMissionItem         (other, flyView, parent)
151 152 153 154
    , _missionItem              (other._vehicle)
    , _rawEdit                  (false)
    , _dirty                    (false)
    , _ignoreDirtyChangeSignals (false)
155 156
    , _speedSection             (nullptr)
    , _cameraSection            (nullptr)
157 158 159 160 161 162 163 164 165
    , _commandTree              (qgcApp()->toolbox()->missionCommandTree())
    , _supportedCommandFact     (0,         "Command:",             FactMetaData::valueTypeUint32)
    , _altitudeMode             (other._altitudeMode)
    , _altitudeFact             (0,         "Altitude",             FactMetaData::valueTypeDouble)
    , _amslAltAboveTerrainFact  (qQNaN(),   "Alt above terrain",    FactMetaData::valueTypeDouble)
    , _param1MetaData           (FactMetaData::valueTypeDouble)
    , _param2MetaData           (FactMetaData::valueTypeDouble)
    , _param3MetaData           (FactMetaData::valueTypeDouble)
    , _param4MetaData           (FactMetaData::valueTypeDouble)
166
    , _syncingHeadingDegreesAndParam4           (false)
167
{
Don Gagne's avatar
Don Gagne committed
168 169
    _editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml");

170 171 172
    _altitudeFact.setRawValue(other._altitudeFact.rawValue());
    _amslAltAboveTerrainFact.setRawValue(other._amslAltAboveTerrainFact.rawValue());

173 174
    _setupMetaData();
    _connectSignals();
175
    _updateOptionalSections();
176
    _rebuildFacts();
177
    setDirty(false);
178 179
}

180 181 182
void SimpleMissionItem::_connectSignals(void)
{
    // Connect to change signals to track dirty state
183 184 185 186 187 188 189 190 191 192 193 194 195 196 197
    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);
198

199 200 201 202
    connect(this, &SimpleMissionItem::sequenceNumberChanged,        this, &SimpleMissionItem::lastSequenceNumberChanged);
    connect(this, &SimpleMissionItem::cameraSectionChanged,         this, &SimpleMissionItem::_setDirty);
    connect(this, &SimpleMissionItem::cameraSectionChanged,         this, &SimpleMissionItem::_updateLastSequenceNumber);

203 204
    connect(this, &SimpleMissionItem::wizardModeChanged,             this, &SimpleMissionItem::readyForSaveStateChanged);

205
    // These are coordinate parameters, they must emit coordinateChanged signal
206 207 208
    connect(&_missionItem._param5Fact,  &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged);
    connect(&_missionItem._param6Fact,  &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged);
    connect(&_missionItem._param7Fact,  &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged);
209

210 211
    connect(&_missionItem._param1Fact,  &Fact::valueChanged, this, &SimpleMissionItem::_possibleAdditionalTimeDelayChanged);

212 213 214 215 216 217
    // 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.
218
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::_setDefaultsForCommand);
219 220
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::commandNameChanged);
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::commandDescriptionChanged);
221
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::abbreviationChanged);
222
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::specifiesCoordinateChanged);
223
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::specifiesAltitudeOnlyChanged);
224 225 226
    connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::isStandaloneCoordinateChanged);

    // Whenever these properties change the ui model changes as well
227 228
    connect(this, &SimpleMissionItem::commandChanged,       this, &SimpleMissionItem::_rebuildFacts);
    connect(this, &SimpleMissionItem::rawEditChanged,       this, &SimpleMissionItem::_rebuildFacts);
229 230 231

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

233 234 235 236 237 238
    // 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);
239 240 241 242 243 244 245 246 247
}

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

    if (!_altitudeMetaData) {
        _altitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble);
248
        _altitudeMetaData->setRawUnits("m");
249
        _altitudeMetaData->setRawIncrement(1);
250 251 252 253
        _altitudeMetaData->setDecimalPlaces(2);

        enumStrings.clear();
        enumValues.clear();
254
        MissionCommandTree* commandTree = qgcApp()->toolbox()->missionCommandTree();
255
        for (const MAV_CMD command: commandTree->allCommandIds()) {
256 257
            enumStrings.append(commandTree->rawName(command));
            enumValues.append(QVariant((int)command));
258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287
        }
        _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);
288
    _altitudeFact.setMetaData(_altitudeMetaData);
289
    _amslAltAboveTerrainFact.setMetaData(_altitudeMetaData);
290 291 292 293 294 295
}

SimpleMissionItem::~SimpleMissionItem()
{    
}

296
void SimpleMissionItem::save(QJsonArray&  missionItems)
297
{
298 299 300 301 302 303 304 305
    QList<MissionItem*> items;

    appendMissionItems(items, this);

    for (int i=0; i<items.count(); i++) {
        MissionItem* item = items[i];
        QJsonObject saveObject;
        item->save(saveObject);
306 307 308 309 310 311 312 313
        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();
            }
        }
314 315 316
        missionItems.append(saveObject);
        item->deleteLater();
    }
317 318 319 320
}

bool SimpleMissionItem::load(QTextStream &loadStream)
{
321 322
    bool success;
    if ((success = _missionItem.load(loadStream))) {
323
        if (specifiesCoordinate()) {
324
            _altitudeMode = _missionItem.relativeAltitude() ? QGroundControlQmlGlobal::AltitudeModeRelative : QGroundControlQmlGlobal::AltitudeModeAbsolute;
325 326 327
            _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue());
            _amslAltAboveTerrainFact.setRawValue(qQNaN());
        }
328 329
        _updateOptionalSections();
    }
330

331
    return success;
332 333
}

Don Gagne's avatar
Don Gagne committed
334
bool SimpleMissionItem::load(const QJsonObject& json, int sequenceNumber, QString& errorString)
335
{
336 337
    if (!_missionItem.load(json, sequenceNumber, errorString)) {
        return false;
338
    }
339 340 341 342 343 344 345 346 347 348 349 350

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

351
            _altitudeMode = (QGroundControlQmlGlobal::AltitudeMode)(int)json[_jsonAltitudeModeKey].toDouble();
352 353 354
            _altitudeFact.setRawValue(JsonHelper::possibleNaNJsonValue(json[_jsonAltitudeKey]));
            _amslAltAboveTerrainFact.setRawValue(JsonHelper::possibleNaNJsonValue(json[_jsonAltitudeKey]));
        } else {
355
            _altitudeMode = _missionItem.relativeAltitude() ? QGroundControlQmlGlobal::AltitudeModeRelative : QGroundControlQmlGlobal::AltitudeModeAbsolute;
356 357 358 359 360 361 362 363
            _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue());
            _amslAltAboveTerrainFact.setRawValue(qQNaN());
        }
    }

    _updateOptionalSections();

    return true;
364 365 366 367
}

bool SimpleMissionItem::isStandaloneCoordinate(void) const
{
368 369 370
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, (MAV_CMD)command());
    if (uiInfo) {
        return uiInfo->isStandaloneCoordinate();
371 372 373 374 375 376 377
    } else {
        return false;
    }
}

bool SimpleMissionItem::specifiesCoordinate(void) const
{
378 379 380
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, (MAV_CMD)command());
    if (uiInfo) {
        return uiInfo->specifiesCoordinate();
381 382 383 384 385
    } else {
        return false;
    }
}

386 387 388 389 390 391 392 393 394 395
bool SimpleMissionItem::specifiesAltitudeOnly(void) const
{
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, (MAV_CMD)command());
    if (uiInfo) {
        return uiInfo->specifiesAltitudeOnly();
    } else {
        return false;
    }
}

396 397
QString SimpleMissionItem::commandDescription(void) const
{
398 399 400
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, (MAV_CMD)command());
    if (uiInfo) {
        return uiInfo->description();
401 402 403 404 405 406 407 408
    } else {
        qWarning() << "Should not ask for command description on unknown command";
        return commandName();
    }
}

QString SimpleMissionItem::commandName(void) const
{
409 410 411
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, (MAV_CMD)command());
    if (uiInfo) {
        return uiInfo->friendlyName();
412 413
    } else {
        qWarning() << "Request for command name on unknown command";
414
        return tr("Unknown: %1").arg(command());
415 416 417
    }
}

418 419 420
QString SimpleMissionItem::abbreviation() const
{
    if (homePosition())
421
        return tr("H");
422 423

    switch(command()) {
424
    case MAV_CMD_NAV_TAKEOFF:
425
        return tr("Takeoff");
426
    case MAV_CMD_NAV_LAND:
427
        return tr("Land");
428
    case MAV_CMD_NAV_VTOL_TAKEOFF:
429
        return tr("VTOL Takeoff");
430
    case MAV_CMD_NAV_VTOL_LAND:
431
        return tr("VTOL Land");
432
    case MAV_CMD_DO_SET_ROI:
433 434 435
        return tr("ROI");
    default:
        return QString();
436 437 438
    }
}

439
void SimpleMissionItem::_rebuildTextFieldFacts(void)
440
{
441
    _textFieldFacts.clear();
442 443
    
    if (rawEdit()) {
444
        _missionItem._param1Fact._setName("Param1");
445
        _missionItem._param1Fact.setMetaData(_defaultParamMetaData);
446
        _textFieldFacts.append(&_missionItem._param1Fact);
447
        _missionItem._param2Fact._setName("Param2");
448
        _missionItem._param2Fact.setMetaData(_defaultParamMetaData);
449
        _textFieldFacts.append(&_missionItem._param2Fact);
450
        _missionItem._param3Fact._setName("Param3");
451
        _missionItem._param3Fact.setMetaData(_defaultParamMetaData);
452
        _textFieldFacts.append(&_missionItem._param3Fact);
453
        _missionItem._param4Fact._setName("Param4");
454
        _missionItem._param4Fact.setMetaData(_defaultParamMetaData);
455
        _textFieldFacts.append(&_missionItem._param4Fact);
456
        _missionItem._param5Fact._setName("Lat/X");
457
        _missionItem._param5Fact.setMetaData(_defaultParamMetaData);
458
        _textFieldFacts.append(&_missionItem._param5Fact);
459
        _missionItem._param6Fact._setName("Lon/Y");
460
        _missionItem._param6Fact.setMetaData(_defaultParamMetaData);
461
        _textFieldFacts.append(&_missionItem._param6Fact);
462
        _missionItem._param7Fact._setName("Alt/Z");
463
        _missionItem._param7Fact.setMetaData(_defaultParamMetaData);
464
        _textFieldFacts.append(&_missionItem._param7Fact);
465
    } else {
466 467
        _ignoreDirtyChangeSignals = true;

468 469 470 471 472 473 474 475 476 477
        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 };

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

480
        for (int i=1; i<=7; i++) {
481 482
            bool showUI;
            const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
483

484
            if (showUI && paramInfo && paramInfo->enumStrings().count() == 0 && !paramInfo->nanUnchanged()) {
485 486 487 488 489 490 491
                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);
492
                _textFieldFacts.append(paramFact);
493 494 495
            }
        }

496
        _ignoreDirtyChangeSignals = false;
497 498 499
    }
}

500
void SimpleMissionItem::_rebuildNaNFacts(void)
501
{
502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519
    _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++) {
520 521
            bool showUI;
            const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
522

523
            if (showUI && paramInfo && paramInfo->nanUnchanged()) {
524 525 526 527 528 529
                // 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;
                }
530
                bool hideWaypointHeading = (command == MAV_CMD_NAV_WAYPOINT || command == MAV_CMD_NAV_TAKEOFF) && (i == 4) && firmwareVehicle->firmwarePlugin()->vehicleYawsToNextWaypointInMission(firmwareVehicle);
531 532 533
                if (hideWaypointHeading) {
                    continue;
                }
534

535 536 537 538 539 540 541 542 543 544 545 546 547 548 549
                Fact*               paramFact =     rgParamFacts[i-1];
                FactMetaData*       paramMetaData = rgParamMetaData[i-1];

                paramFact->_setName(paramInfo->label());
                paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces());
                paramMetaData->setRawUnits(paramInfo->units());
                paramFact->setMetaData(paramMetaData);
                _nanFacts.append(paramFact);
            }
        }

        _ignoreDirtyChangeSignals = false;
    }
}

550
bool SimpleMissionItem::specifiesAltitude(void) const
551
{
552
    return specifiesCoordinate() || specifiesAltitudeOnly();
553 554
}

555
void SimpleMissionItem::_rebuildComboBoxFacts(void)
556
{
557
    _comboboxFacts.clear();
558 559

    if (rawEdit()) {
560 561
        _comboboxFacts.append(&_missionItem._commandFact);
        _comboboxFacts.append(&_missionItem._frameFact);
562 563 564 565 566 567 568 569 570 571 572 573
    } 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++) {
574 575
            bool showUI;
            const MissionCmdParamInfo* paramInfo = _commandTree->getUIInfo(_vehicle, command)->getParamInfo(i, showUI);
576

577
            if (showUI && paramInfo && paramInfo->enumStrings().count() != 0) {
578 579 580 581 582 583 584 585
                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);
586
                _comboboxFacts.append(paramFact);
587 588 589
            }
        }
    }
590
}
591

592 593 594 595 596
void SimpleMissionItem::_rebuildFacts(void)
{
    _rebuildTextFieldFacts();
    _rebuildNaNFacts();
    _rebuildComboBoxFacts();
597 598 599 600
}

bool SimpleMissionItem::friendlyEditAllowed(void) const
{
601
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, static_cast<MAV_CMD>(command()));
602
    if (uiInfo && uiInfo->friendlyEdit()) {
603 604 605 606
        if (!_missionItem.autoContinue()) {
            return false;
        }

607
        if (specifiesCoordinate() || specifiesAltitudeOnly()) {
608 609 610 611 612 613
            MAV_FRAME frame = _missionItem.frame();
            switch (frame) {
            case MAV_FRAME_GLOBAL:
            case MAV_FRAME_GLOBAL_RELATIVE_ALT:
                return true;

614 615
            case MAV_FRAME_GLOBAL_TERRAIN_ALT:
                return supportsTerrainFrame();
616 617 618
            default:
                return false;
            }
619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641
        }

        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)
{
642
    if (!_homePositionSpecialCase || (_dirty != dirty)) {
643
        _dirty = dirty;
644 645 646 647
        if (!dirty) {
            _cameraSection->setDirty(false);
            _speedSection->setDirty(false);
        }
648
        emit dirtyChanged(dirty);
649 650 651
    }
}

652
void SimpleMissionItem::_setDirty(void)
653
{
654 655 656
    if (!_ignoreDirtyChangeSignals) {
        setDirty(true);
    }
657 658 659 660 661 662 663
}

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

664
void SimpleMissionItem::_altitudeModeChanged(void)
665
{
666
    switch (_altitudeMode) {
667
    case QGroundControlQmlGlobal::AltitudeModeTerrainFrame:
668 669
        _missionItem.setFrame(MAV_FRAME_GLOBAL_TERRAIN_ALT);
        break;
670
    case QGroundControlQmlGlobal::AltitudeModeAboveTerrain:
671
        // Terrain altitudes are Absolute
672
        _missionItem.setFrame(MAV_FRAME_GLOBAL);
673
        // Clear any old calculated values
674 675 676
        _missionItem._param7Fact.setRawValue(qQNaN());
        _amslAltAboveTerrainFact.setRawValue(qQNaN());
        break;
677
    case QGroundControlQmlGlobal::AltitudeModeAbsolute:
678 679
        _missionItem.setFrame(MAV_FRAME_GLOBAL);
        break;
680
    case QGroundControlQmlGlobal::AltitudeModeRelative:
681 682
        _missionItem.setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
        break;
Don Gagne's avatar
Don Gagne committed
683 684 685
    case QGroundControlQmlGlobal::AltitudeModeNone:
        qWarning() << "Internal Error SimpleMissionItem::_altitudeModeChanged: Invalid altitudeMode == AltitudeModeNone";
        break;
686
    }
687 688 689 690

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

691
    emit coordinateHasRelativeAltitudeChanged(_altitudeMode == QGroundControlQmlGlobal::AltitudeModeRelative);
692 693
}

694
void SimpleMissionItem::_altitudeChanged(void)
695
{
696 697 698 699
    if (!specifiesAltitude()) {
        return;
    }

700
    if (_altitudeMode == QGroundControlQmlGlobal::AltitudeModeAboveTerrain) {
701
        _amslAltAboveTerrainFact.setRawValue(qQNaN());
702 703 704
        _terrainAltChanged();
    } else {
        _missionItem._param7Fact.setRawValue(_altitudeFact.rawValue());
705 706 707
    }
}

708 709
void SimpleMissionItem::_terrainAltChanged(void)
{
710
    if (!specifiesAltitude() || _altitudeMode != QGroundControlQmlGlobal::AltitudeModeAboveTerrain) {
711 712 713 714 715 716 717 718 719
        // 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 {
720 721 722 723 724 725
        double newAboveTerrain = terrainAltitude() + _altitudeFact.rawValue().toDouble();
        double oldAboveTerrain = _amslAltAboveTerrainFact.rawValue().toDouble();
        if (qIsNaN(oldAboveTerrain) || !qFuzzyCompare(newAboveTerrain, oldAboveTerrain)) {
            _missionItem._param7Fact.setRawValue(newAboveTerrain);
            _amslAltAboveTerrainFact.setRawValue(newAboveTerrain);
        }
726
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
727
    emit readyForSaveStateChanged();
728 729
}

DonLakeFlyer's avatar
DonLakeFlyer committed
730
SimpleMissionItem::ReadyForSaveState SimpleMissionItem::readyForSaveState(void) const
731
{
732 733 734 735
    if (_wizardMode) {
        return NotReadyForSaveData;
    }

DonLakeFlyer's avatar
DonLakeFlyer committed
736 737
    bool terrainReady =  !specifiesAltitude() || !qIsNaN(_missionItem._param7Fact.rawValue().toDouble());
    return terrainReady ? ReadyForSave : NotReadyForSaveTerrain;
738 739
}

740
void SimpleMissionItem::_setDefaultsForCommand(void)
741
{
742 743 744 745 746 747 748 749 750 751
    // 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);
752 753 754 755
    } 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());
756 757 758
    }

    // Set global defaults first, then if there are param defaults they will get reset
759
    _altitudeMode = QGroundControlQmlGlobal::AltitudeModeRelative;
DonLakeFlyer's avatar
DonLakeFlyer committed
760
    emit altitudeModeChanged();
761
    _amslAltAboveTerrainFact.setRawValue(qQNaN());
762 763 764 765 766 767 768 769
    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);
    }
770

771
    MAV_CMD command = static_cast<MAV_CMD>(this->command());
772 773 774
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, command);
    if (uiInfo) {
        for (int i=1; i<=7; i++) {
775 776
            bool showUI;
            const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
777 778 779 780
            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());
            }
781 782 783
        }
    }

784 785
    switch (command) {
    case MAV_CMD_NAV_WAYPOINT:
786 787 788
        // We default all acceptance radius to 0. This allows flight controller to be in control of
        // accept radius.
        _missionItem.setParam2(0);
789 790 791
        break;

    case MAV_CMD_NAV_LAND:
Don Gagne's avatar
Don Gagne committed
792
    case MAV_CMD_NAV_VTOL_LAND:
Don Gagne's avatar
Don Gagne committed
793
    case MAV_CMD_DO_SET_ROI_LOCATION:
DonLakeFlyer's avatar
DonLakeFlyer committed
794
        _altitudeFact.setRawValue(0);
795 796
        _missionItem.setParam7(0);
        break;
Donald Gagne's avatar
Donald Gagne committed
797 798
    default:
        break;
799 800 801
    }

    _missionItem.setAutoContinue(true);
802
    _missionItem.setFrame((specifiesCoordinate() || specifiesAltitudeOnly()) ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_MISSION);
803 804 805 806 807 808 809 810 811 812 813 814 815 816 817
    setRawEdit(false);
}

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

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

QString SimpleMissionItem::category(void) const
{
818
    return _commandTree->getUIInfo(_vehicle, static_cast<MAV_CMD>(command()))->category();
819 820
}

821
void SimpleMissionItem::setCommand(int command)
822
{
823 824
    if (static_cast<MAV_CMD>(command) != _missionItem.command()) {
        _missionItem.setCommand(static_cast<MAV_CMD>(command));
825
        _updateOptionalSections();
826 827 828 829 830
    }
}

void SimpleMissionItem::setCoordinate(const QGeoCoordinate& coordinate)
{
831 832 833 834
    // 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());
835 836
    }
}
837 838 839

void SimpleMissionItem::setSequenceNumber(int sequenceNumber)
{
840 841 842 843 844 845
    if (_missionItem.sequenceNumber() != sequenceNumber) {
        _missionItem.setSequenceNumber(sequenceNumber);
        emit sequenceNumberChanged(sequenceNumber);
        // This is too likely to ignore
        emit abbreviationChanged();
    }
846
}
847

DonLakeFlyer's avatar
DonLakeFlyer committed
848
double SimpleMissionItem::specifiedFlightSpeed(void)
849
{
850 851 852 853 854
    if (_speedSection->specifyFlightSpeed()) {
        return _speedSection->flightSpeed()->rawValue().toDouble();
    } else {
        return missionItem().specifiedFlightSpeed();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
855 856 857 858 859
}

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

862 863 864 865 866
double SimpleMissionItem::specifiedGimbalPitch(void)
{
    return _cameraSection->available() ? _cameraSection->specifiedGimbalPitch() : missionItem().specifiedGimbalPitch();
}

867
bool SimpleMissionItem::scanForSections(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle)
868
{
869
    bool sectionFound = false;
870

871
    Q_UNUSED(vehicle);
872 873

    if (_cameraSection->available()) {
874 875 876 877
        sectionFound |= _cameraSection->scanForSection(visualItems, scanIndex);
    }
    if (_speedSection->available()) {
        sectionFound |= _speedSection->scanForSection(visualItems, scanIndex);
878
    }
879 880

    return sectionFound;
881 882
}

883
void SimpleMissionItem::_updateOptionalSections(void)
884
{
885
    // Remove previous sections
886 887
    if (_cameraSection) {
        _cameraSection->deleteLater();
888
        _cameraSection = nullptr;
889
    }
890 891
    if (_speedSection) {
        _speedSection->deleteLater();
892
        _speedSection = nullptr;
893
    }
894

895 896 897 898
    // Add new sections

    _cameraSection = new CameraSection(_vehicle, this);
    _speedSection = new SpeedSection(_vehicle, this);
899
    if (static_cast<MAV_CMD>(command()) == MAV_CMD_NAV_WAYPOINT) {
900
        _cameraSection->setAvailable(true);
901
        _speedSection->setAvailable(true);
902 903
    }

904 905 906 907 908 909
    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);
910

911 912 913
    connect(_speedSection,  &SpeedSection::dirtyChanged,                this, &SimpleMissionItem::_sectionDirtyChanged);
    connect(_speedSection,  &SpeedSection::itemCountChanged,            this, &SimpleMissionItem::_updateLastSequenceNumber);
    connect(_speedSection,  &SpeedSection::specifiedFlightSpeedChanged, this, &SimpleMissionItem::specifiedFlightSpeedChanged);
914

915
    emit cameraSectionChanged(_cameraSection);
916
    emit speedSectionChanged(_speedSection);
917
    emit lastSequenceNumberChanged(lastSequenceNumber());
918 919 920 921
}

int SimpleMissionItem::lastSequenceNumber(void) const
{
922
    return sequenceNumber() + (_cameraSection ? _cameraSection->itemCount() : 0) + (_speedSection ? _speedSection->itemCount() : 0);
923 924 925 926 927 928 929
}

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

930
void SimpleMissionItem::_sectionDirtyChanged(bool dirty)
931 932 933 934 935 936 937 938 939 940 941 942 943
{
    if (dirty) {
        setDirty(true);
    }
}

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

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

944 945
    _cameraSection->appendSectionItems(items, missionItemParent, seqNum);
    _speedSection->appendSectionItems(items, missionItemParent, seqNum);
946
}
DonLakeFlyer's avatar
DonLakeFlyer committed
947 948 949

void SimpleMissionItem::applyNewAltitude(double newAltitude)
{
950
    MAV_CMD command = static_cast<MAV_CMD>(this->command());
DonLakeFlyer's avatar
DonLakeFlyer committed
951 952 953
    const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, command);

    if (uiInfo->specifiesCoordinate() || uiInfo->specifiesAltitudeOnly()) {
954
        switch (static_cast<MAV_CMD>(this->command())) {
DonLakeFlyer's avatar
DonLakeFlyer committed
955 956 957 958 959
        case MAV_CMD_NAV_LAND:
        case MAV_CMD_NAV_VTOL_LAND:
            // Leave alone
            break;
        default:
960
            _altitudeFact.setRawValue(newAltitude);
DonLakeFlyer's avatar
DonLakeFlyer committed
961 962 963 964
            break;
        }
    }
}
965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981

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

983
void SimpleMissionItem::setAltitudeMode(QGroundControlQmlGlobal::AltitudeMode altitudeMode)
984 985 986 987 988 989
{
    if (altitudeMode != _altitudeMode) {
        _altitudeMode = altitudeMode;
        emit altitudeModeChanged();
    }
}
990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014

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