MissionController.cc 69.6 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 14


#include "MissionController.h"
#include "MultiVehicleManager.h"
#include "MissionManager.h"
#include "CoordinateVector.h"
15
#include "FirmwarePlugin.h"
16
#include "QGCApplication.h"
17
#include "SimpleMissionItem.h"
18
#include "SurveyMissionItem.h"
19
#include "FixedWingLandingComplexItem.h"
20
#include "JsonHelper.h"
21
#include "ParameterManager.h"
22
#include "QGroundControlQmlGlobal.h"
23
#include "SettingsManager.h"
24
#include "AppSettings.h"
25
#include "MissionSettingsItem.h"
26
#include "QGCQGeoCoordinate.h"
27
#include "PlanMasterController.h"
28

29
#ifndef __mobile__
30
#include "MainWindow.h"
31
#include "QGCQFileDialog.h"
32 33
#endif

34 35
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

36
const char* MissionController::_settingsGroup =                 "MissionController";
Don Gagne's avatar
Don Gagne committed
37 38
const char* MissionController::_jsonFileTypeValue =             "Mission";
const char* MissionController::_jsonItemsKey =                  "items";
39
const char* MissionController::_jsonPlannedHomePositionKey =    "plannedHomePosition";
Don Gagne's avatar
Don Gagne committed
40
const char* MissionController::_jsonFirmwareTypeKey =           "firmwareType";
41 42 43
const char* MissionController::_jsonVehicleTypeKey =            "vehicleType";
const char* MissionController::_jsonCruiseSpeedKey =            "cruiseSpeed";
const char* MissionController::_jsonHoverSpeedKey =             "hoverSpeed";
Don Gagne's avatar
Don Gagne committed
44 45 46 47 48 49 50
const char* MissionController::_jsonParamsKey =                 "params";

// Deprecated V1 format keys
const char* MissionController::_jsonComplexItemsKey =           "complexItems";
const char* MissionController::_jsonMavAutopilotKey =           "MAV_AUTOPILOT";

const int   MissionController::_missionFileVersion =            2;
51

52 53 54
MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
    : PlanElementController(masterController, parent)
    , _missionManager(_managerVehicle->missionManager())
55
    , _visualItems(NULL)
56
    , _settingsItem(NULL)
57
    , _firstItemsFromVehicle(false)
DonLakeFlyer's avatar
DonLakeFlyer committed
58
    , _itemsRequested(false)
59 60
    , _surveyMissionItemName(tr("Survey"))
    , _fwLandingMissionItemName(tr("Fixed Wing Landing"))
61
    , _appSettings(qgcApp()->toolbox()->settingsManager()->appSettings())
62
    , _progressPct(0)
63
{
64
    _resetMissionFlightStatus();
65
    managerVehicleChanged(_managerVehicle);
66 67 68 69
}

MissionController::~MissionController()
{
Don Gagne's avatar
Don Gagne committed
70

71 72
}

73 74 75 76 77 78 79 80 81
void MissionController::_resetMissionFlightStatus(void)
{
    _missionFlightStatus.totalDistance =        0.0;
    _missionFlightStatus.maxTelemetryDistance = 0.0;
    _missionFlightStatus.totalTime =            0.0;
    _missionFlightStatus.hoverTime =            0.0;
    _missionFlightStatus.cruiseTime =           0.0;
    _missionFlightStatus.hoverDistance =        0.0;
    _missionFlightStatus.cruiseDistance =       0.0;
82 83 84
    _missionFlightStatus.cruiseSpeed =          _controllerVehicle->defaultCruiseSpeed();
    _missionFlightStatus.hoverSpeed =           _controllerVehicle->defaultHoverSpeed();
    _missionFlightStatus.vehicleSpeed =         _controllerVehicle->multiRotor() || _managerVehicle->vtol() ? _missionFlightStatus.hoverSpeed : _missionFlightStatus.cruiseSpeed;
85
    _missionFlightStatus.vehicleYaw =           0.0;
86 87 88 89 90 91 92 93 94 95 96 97 98
    _missionFlightStatus.gimbalYaw =            std::numeric_limits<double>::quiet_NaN();

    // Battery information

    _missionFlightStatus.mAhBattery =           0;
    _missionFlightStatus.hoverAmps =            0;
    _missionFlightStatus.cruiseAmps =           0;
    _missionFlightStatus.ampMinutesAvailable =  0;
    _missionFlightStatus.hoverAmpsTotal =       0;
    _missionFlightStatus.cruiseAmpsTotal =      0;
    _missionFlightStatus.batteryChangePoint =   -1;
    _missionFlightStatus.batteriesRequired =    -1;

99 100 101 102
    _controllerVehicle->firmwarePlugin()->batteryConsumptionData(_controllerVehicle, _missionFlightStatus.mAhBattery, _missionFlightStatus.hoverAmps, _missionFlightStatus.cruiseAmps);
    if (_missionFlightStatus.mAhBattery != 0) {
        double batteryPercentRemainingAnnounce = qgcApp()->toolbox()->settingsManager()->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toDouble();
        _missionFlightStatus.ampMinutesAvailable = (double)_missionFlightStatus.mAhBattery / 1000.0 * 60.0 * ((100.0 - batteryPercentRemainingAnnounce) / 100.0);
103
    }
104 105 106 107 108 109 110 111 112 113 114

    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionTimeChanged();
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);

115 116
}

117 118
void MissionController::start(bool editMode)
{
119 120
    qCDebug(MissionControllerLog) << "start editMode" << editMode;

121
    PlanElementController::start(editMode);
122 123 124 125 126
    _init();
}

void MissionController::_init(void)
{
127
    // We start with an empty mission
128
    _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
129
    _addMissionSettings(_visualItems, false /* addToCenter */);
130
    _initAllVisualItems();
131 132
}

133
// Called when new mission items have completed downloading from Vehicle
134
void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllRequested)
135
{
136 137
    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";

DonLakeFlyer's avatar
DonLakeFlyer committed
138 139 140
    // Fly view always reloads on _loadComplete
    // Plan view only reloads on _loadComplete if specifically requested
    if (!_editMode || removeAllRequested || _itemsRequested) {
141
        // Fly Mode (accept if):
Don Gagne's avatar
Don Gagne committed
142
        //      - Always accepts new items from the vehicle so Fly view is kept up to date
143
        // Edit Mode (accept if):
144
        //      - Either a load from vehicle was manually requested or
Don Gagne's avatar
Don Gagne committed
145
        //      - The initial automatic load from a vehicle completed and the current editor is empty
146
        //      - Remove all way requested from Fly view (clear mission on flight end)
147

148
        QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
149
        const QList<MissionItem*>& newMissionItems = _missionManager->missionItems();
150 151 152
        qCDebug(MissionControllerLog) << "loading from vehicle: count"<< newMissionItems.count();

        int i = 0;
153
        if (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() && newMissionItems.count() != 0) {
154
            // First item is fake home position
DonLakeFlyer's avatar
DonLakeFlyer committed
155
            _addMissionSettings(newControllerMissionItems, false /* addToCenter */);
156
            MissionSettingsItem* settingsItem = newControllerMissionItems->value<MissionSettingsItem*>(0);
157 158 159 160 161 162 163
            if (!settingsItem) {
                qWarning() << "First item is not settings item";
                return;
            }
            settingsItem->setCoordinate(newMissionItems[0]->coordinate());
            i = 1;
        }
164

165 166
        for (; i<newMissionItems.count(); i++) {
            const MissionItem* missionItem = newMissionItems[i];
167
            newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, *missionItem, this));
168 169 170
        }

        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
171
        _visualItems->deleteLater();
172
        _settingsItem = NULL;
173 174
        _visualItems = NULL;
        _updateContainsItems(); // This will clear containsItems which will be set again below. This will re-pop Start Mission confirmation.
175 176
        _visualItems = newControllerMissionItems;

177
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
DonLakeFlyer's avatar
DonLakeFlyer committed
178
            _addMissionSettings(_visualItems, _editMode && _visualItems->count() > 0 /* addToCenter */);
179 180
        }

181
        if (_editMode) {
182
            MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
183
        }
184

185
        _initAllVisualItems();
186
        _updateContainsItems();
187
        emit newItemsFromVehicle();
188
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
189
    _itemsRequested = false;
190 191
}

192
void MissionController::loadFromVehicle(void)
193
{
DonLakeFlyer's avatar
DonLakeFlyer committed
194 195 196 197 198 199 200 201
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::loadFromVehicle called while offline";
    } else if (syncInProgress()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::loadFromVehicle called while syncInProgress";
    } else {
        _itemsRequested = true;
        _managerVehicle->missionManager()->loadFromVehicle();
    }
202 203
}

204
void MissionController::sendToVehicle(void)
205
{
DonLakeFlyer's avatar
DonLakeFlyer committed
206 207 208 209 210
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::sendToVehicle called while offline";
    } else if (syncInProgress()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::sendToVehicle called while syncInProgress";
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
211
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
DonLakeFlyer's avatar
DonLakeFlyer committed
212 213 214 215 216 217 218 219 220
        if (_visualItems->count() == 1) {
            // This prevents us from sending a possibly bogus home position to the vehicle
            QmlObjectListModel emptyModel;
            sendItemsToVehicle(_managerVehicle, &emptyModel);
        } else {
            sendItemsToVehicle(_managerVehicle, _visualItems);
        }
        setDirty(false);
    }
Don Gagne's avatar
Don Gagne committed
221 222
}

223 224 225 226 227
/// Converts from visual items to MissionItems
///     @param missionItemParent QObject parent for newly allocated MissionItems
/// @return true: Mission end action was added to end of list
bool MissionController::_convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
228 229 230 231
    if (visualMissionItems->count() == 0) {
        return false;
    }

232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247
    bool endActionSet = false;
    int lastSeqNum = 0;

    for (int i=0; i<visualMissionItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(visualMissionItems->get(i));

        lastSeqNum = visualItem->lastSequenceNumber();
        visualItem->appendMissionItems(rgMissionItems, missionItemParent);

        qCDebug(MissionControllerLog) << "_convertToMissionItems seqNum:lastSeqNum:command"
                                      << visualItem->sequenceNumber()
                                      << lastSeqNum
                                      << visualItem->commandName();
    }

    // Mission settings has a special case for end mission action
248
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
249 250 251 252 253 254 255
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

Don Gagne's avatar
Don Gagne committed
256 257 258
void MissionController::sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems)
{
    if (vehicle) {
259
        QList<MissionItem*> rgMissionItems;
260

261
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
262

263
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
264

265 266
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
267
        }
268 269
    }
}
270

271 272 273 274 275 276
int MissionController::_nextSequenceNumber(void)
{
    if (_visualItems->count() == 0) {
        qWarning() << "Internal error: Empty visual item list";
        return 0;
    } else {
277 278
        VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
        return lastItem->lastSequenceNumber() + 1;
279 280 281
    }
}

282
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
283
{
284
    int sequenceNumber = _nextSequenceNumber();
285
    SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, this);
286
    newItem->setSequenceNumber(sequenceNumber);
287
    newItem->setCoordinate(coordinate);
288 289 290
    newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
    _initVisualItem(newItem);
    if (_visualItems->count() == 1) {
291
        newItem->setCommand(_controllerVehicle->vtol() ? MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF : MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
292
    }
293
    newItem->setDefaultsForCommand();
Don Gagne's avatar
Don Gagne committed
294
    if ((MAV_CMD)newItem->command() == MAV_CMD_NAV_WAYPOINT) {
295 296
        double      prevAltitude;
        MAV_FRAME   prevFrame;
297

298 299 300
        if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
            newItem->missionItem().setFrame(prevFrame);
            newItem->missionItem().setParam7(prevAltitude);
301
        }
302
    }
303
    _visualItems->insert(i, newItem);
304 305 306

    _recalcAll();

307
    return newItem->sequenceNumber();
308 309
}

310
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
311
{
312 313
    ComplexMissionItem* newItem;

314
    int sequenceNumber = _nextSequenceNumber();
315
    if (itemName == _surveyMissionItemName) {
316
        newItem = new SurveyMissionItem(_controllerVehicle, _visualItems);
317
        newItem->setCoordinate(mapCenterCoordinate);
318 319 320 321
        // If the vehicle is known to have a gimbal then we automatically point the gimbal straight down if not already set
        bool rollSupported = false;
        bool pitchSupported = false;
        bool yawSupported = false;
322 323 324
        MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
        CameraSection* cameraSection = settingsItem->cameraSection();
        // Set camera to photo mode (leave alone if user already specified)
325
        if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
326 327 328 329
            cameraSection->setSpecifyCameraMode(true);
            cameraSection->cameraMode()->setRawValue(0);
        }
        // Point gimbal straight down
330
        if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
331 332 333
            // If the user already specified a gimbal angle leave it alone
            if (!cameraSection->specifyGimbal()) {
                cameraSection->setSpecifyGimbal(true);
334
                cameraSection->gimbalPitch()->setRawValue(-90.0);
335 336
            }
        }
337
    } else if (itemName == _fwLandingMissionItemName) {
338
        newItem = new FixedWingLandingComplexItem(_controllerVehicle, _visualItems);
339 340 341 342
    } else {
        qWarning() << "Internal error: Unknown complex item:" << itemName;
        return sequenceNumber;
    }
343
    newItem->setSequenceNumber(sequenceNumber);
344
    _initVisualItem(newItem);
345

346
    _visualItems->insert(i, newItem);
347 348 349

    _recalcAll();

350
    return newItem->sequenceNumber();
351 352
}

353 354
void MissionController::removeMissionItem(int index)
{
355 356 357 358 359 360
    if (index <= 0 || index >= _visualItems->count()) {
        qWarning() << "MissionController::removeMissionItem called with bad index - count:index" << _visualItems->count() << index;
        return;
    }

    bool surveyRemoved = _visualItems->value<SurveyMissionItem*>(index);
361
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
362

363
    _deinitVisualItem(item);
364
    item->deleteLater();
365

366 367 368 369 370 371 372 373 374 375
    if (surveyRemoved) {
        // Determine if the mission still has another survey in it
        bool foundSurvey = false;
        for (int i=1; i<_visualItems->count(); i++) {
            if (_visualItems->value<SurveyMissionItem*>(i)) {
                foundSurvey = true;
                break;
            }
        }

376
        // If there is no longer a survey item in the mission remove added commands
377 378 379 380
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
381 382
            MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
            CameraSection* cameraSection = settingsItem->cameraSection();
383
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
384
                if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
385 386 387
                    cameraSection->setSpecifyGimbal(false);
                }
            }
388
            if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
389 390
                cameraSection->setSpecifyCameraMode(false);
            }
391 392 393
        }
    }

394
    _recalcAll();
395
    setDirty(true);
396 397
}

398
void MissionController::removeAll(void)
399
{
400 401
    if (_visualItems) {
        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
402
        _visualItems->deleteLater();
403
        _settingsItem = NULL;
404
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
405
        _addMissionSettings(_visualItems, false /* addToCenter */);
406
        _initAllVisualItems();
407
        setDirty(true);
408
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
409 410 411
    }
}

412
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
413 414 415 416 417 418 419 420 421
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Object, true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonMavAutopilotKey,             QJsonValue::Double, true },
        { _jsonComplexItemsKey,             QJsonValue::Array,  true },
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
422 423 424
        return false;
    }

425
    // Read complex items
426
    QList<SurveyMissionItem*> surveyItems;
427 428 429 430
    QJsonArray complexArray(json[_jsonComplexItemsKey].toArray());
    qCDebug(MissionControllerLog) << "Json load: complex item count" << complexArray.count();
    for (int i=0; i<complexArray.count(); i++) {
        const QJsonValue& itemValue = complexArray[i];
431

432 433 434 435 436
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

437
        SurveyMissionItem* item = new SurveyMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
438 439
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
440
            surveyItems.append(item);
441 442
        } else {
            return false;
443
        }
444
    }
445

446 447 448 449 450
    // Read simple items, interspersing complex items into the full list

    int nextSimpleItemIndex= 0;
    int nextComplexItemIndex= 0;
    int nextSequenceNumber = 1; // Start with 1 since home is in 0
Don Gagne's avatar
Don Gagne committed
451
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
452

453
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
454 455 456 457
    do {
        qCDebug(MissionControllerLog) << "Json load: simple item loop nextSimpleItemIndex:nextComplexItemIndex:nextSequenceNumber" << nextSimpleItemIndex << nextComplexItemIndex << nextSequenceNumber;

        // If there is a complex item that should be next in sequence add it in
458 459
        if (nextComplexItemIndex < surveyItems.count()) {
            SurveyMissionItem* complexItem = surveyItems[nextComplexItemIndex];
460 461 462 463 464 465 466 467 468 469 470 471 472 473

            if (complexItem->sequenceNumber() == nextSequenceNumber) {
                qCDebug(MissionControllerLog) << "Json load: injecting complex item expectedSequence:actualSequence:" << nextSequenceNumber << complexItem->sequenceNumber();
                visualItems->append(complexItem);
                nextSequenceNumber = complexItem->lastSequenceNumber() + 1;
                nextComplexItemIndex++;
                continue;
            }
        }

        // Add the next available simple item
        if (nextSimpleItemIndex < itemArray.count()) {
            const QJsonValue& itemValue = itemArray[nextSimpleItemIndex++];

474 475 476 477 478
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
479
            const QJsonObject itemObject = itemValue.toObject();
480
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
481
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
482
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
483
                nextSequenceNumber = item->lastSequenceNumber() + 1;
484
                visualItems->append(item);
485 486 487 488
            } else {
                return false;
            }
        }
489
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
490 491

    if (json.contains(_jsonPlannedHomePositionKey)) {
492
        SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
493

Don Gagne's avatar
Don Gagne committed
494
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
495
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
496 497 498
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
499 500 501 502
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
503
        _addMissionSettings(visualItems, true /* addToCenter */);
504 505 506 507 508
    }

    return true;
}

509
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
510 511 512 513 514 515
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
516
        { _jsonVehicleTypeKey,              QJsonValue::Double, false },
517 518
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
519 520 521 522 523 524 525
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

    qCDebug(MissionControllerLog) << "MissionController::_loadJsonMissionFileV2 itemCount:" << json[_jsonItemsKey].toArray().count();

526
    // Mission Settings
527
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
528

529 530
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
531 532 533 534
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType((MAV_AUTOPILOT)json[_jsonFirmwareTypeKey].toInt()));
        if (json.contains(_jsonVehicleTypeKey)) {
            appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType((MAV_TYPE)json[_jsonVehicleTypeKey].toInt()));
        }
535
    }
536
    if (json.contains(_jsonCruiseSpeedKey)) {
537
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
538 539
    }
    if (json.contains(_jsonHoverSpeedKey)) {
540
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
541 542
    }

543 544 545 546 547
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
548 549
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575
    qCDebug(MissionControllerLog) << "plannedHomePosition" << homeCoordinate;

    // Read mission items

    int nextSequenceNumber = 1; // Start with 1 since home is in 0
    const QJsonArray rgMissionItems(json[_jsonItemsKey].toArray());
    for (int i=0; i<rgMissionItems.count(); i++) {
        // Convert to QJsonObject
        const QJsonValue& itemValue = rgMissionItems[i];
        if (!itemValue.isObject()) {
            errorString = tr("Mission item %1 is not an object").arg(i);
            return false;
        }
        const QJsonObject itemObject = itemValue.toObject();

        // Load item based on type

        QList<JsonHelper::KeyValidateInfo> itemKeyInfoList = {
            { VisualMissionItem::jsonTypeKey,  QJsonValue::String, true },
        };
        if (!JsonHelper::validateKeys(itemObject, itemKeyInfoList, errorString)) {
            return false;
        }
        QString itemType = itemObject[VisualMissionItem::jsonTypeKey].toString();

        if (itemType == VisualMissionItem::jsonTypeSimpleItemValue) {
576
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, visualItems);
577
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
578
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
579
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
580 581 582 583 584 585 586 587 588 589 590 591 592 593 594
                visualItems->append(simpleItem);
            } else {
                return false;
            }
        } else if (itemType == VisualMissionItem::jsonTypeComplexItemValue) {
            QList<JsonHelper::KeyValidateInfo> complexItemKeyInfoList = {
                { ComplexMissionItem::jsonComplexItemTypeKey,  QJsonValue::String, true },
            };
            if (!JsonHelper::validateKeys(itemObject, complexItemKeyInfoList, errorString)) {
                return false;
            }
            QString complexItemType = itemObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();

            if (complexItemType == SurveyMissionItem::jsonComplexItemTypeValue) {
                qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
595
                SurveyMissionItem* surveyItem = new SurveyMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
596 597 598 599 600 601
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
602
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
603
                qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
604
                FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
605 606 607 608 609 610
                if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(landingItem);
611
            } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
612
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
613
                MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
614 615 616 617 618 619
                if (!settingsItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = settingsItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Mission Settings load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(settingsItem);
Don Gagne's avatar
Don Gagne committed
620 621 622 623 624 625 626 627 628 629 630 631 632
            } else {
                errorString = tr("Unsupported complex item type: %1").arg(complexItemType);
            }
        } else {
            errorString = tr("Unknown item type: %1").arg(itemType);
            return false;
        }
    }

    // Fix up the DO_JUMP commands jump sequence number by finding the item with the matching doJumpId
    for (int i=0; i<visualItems->count(); i++) {
        if (visualItems->value<VisualMissionItem*>(i)->isSimpleItem()) {
            SimpleMissionItem* doJumpItem = visualItems->value<SimpleMissionItem*>(i);
Don Gagne's avatar
Don Gagne committed
633
            if ((MAV_CMD)doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656
                bool found = false;
                int findDoJumpId = doJumpItem->missionItem().param1();
                for (int j=0; j<visualItems->count(); j++) {
                    if (visualItems->value<VisualMissionItem*>(j)->isSimpleItem()) {
                        SimpleMissionItem* targetItem = visualItems->value<SimpleMissionItem*>(j);
                        if (targetItem->missionItem().doJumpId() == findDoJumpId) {
                            doJumpItem->missionItem().setParam1(targetItem->sequenceNumber());
                            found = true;
                            break;
                        }
                    }
                }
                if (!found) {
                    errorString = tr("Could not find doJumpId: %1").arg(findDoJumpId);
                    return false;
                }
            }
        }
    }

    return true;
}

657 658 659 660 661 662 663 664
bool MissionController::_loadItemsFromJson(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
{
    // V1 file format has no file type key and version key is string. Convert to new format.
    if (!json.contains(JsonHelper::jsonFileTypeKey)) {
        json[JsonHelper::jsonFileTypeKey] = _jsonFileTypeValue;
    }

    int fileVersion;
665 666 667 668 669 670
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
671 672

    if (fileVersion == 1) {
673
        return _loadJsonMissionFileV1(json, visualItems, errorString);
674
    } else {
675
        return _loadJsonMissionFileV2(json, visualItems, errorString);
676 677 678
    }
}

679
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
680
{
681 682
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
683 684 685 686 687 688 689 690 691

    QString firstLine = stream.readLine();
    const QStringList& version = firstLine.split(" ");

    bool versionOk = false;
    if (version.size() == 3 && version[0] == "QGC" && version[1] == "WPL") {
        if (version[2] == "110") {
            // ArduPilot file, planned home position is already in position 0
            versionOk = true;
692
            plannedHomePositionInFile = true;
693 694 695
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
696
            plannedHomePositionInFile = false;
697 698 699 700
        }
    }

    if (versionOk) {
701
        // Start with planned home in center
DonLakeFlyer's avatar
DonLakeFlyer committed
702
        _addMissionSettings(visualItems, true /* addToCenter */);
703 704
        MissionSettingsItem* settingsItem = visualItems->value<MissionSettingsItem*>(0);

705
        while (!stream.atEnd()) {
706
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
707 708

            if (item->load(stream)) {
709 710 711 712 713 714
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
715 716 717 718 719 720
            } else {
                errorString = QStringLiteral("The mission file is corrupted.");
                return false;
            }
        }
    } else {
721
        errorString = QStringLiteral("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
722 723 724
        return false;
    }

725
    if (!plannedHomePositionInFile) {
726 727 728 729 730
        // Update sequence numbers in DO_JUMP commands to take into account added home position in index 0
        for (int i=1; i<visualItems->count(); i++) {
            SimpleMissionItem* item = qobject_cast<SimpleMissionItem*>(visualItems->get(i));
            if (item && item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) {
                item->missionItem().setParam1((int)item->missionItem().param1() + 1);
Don Gagne's avatar
Don Gagne committed
731 732
            }
        }
733 734 735
    }

    return true;
736 737
}

738
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
739
{
Don Gagne's avatar
Don Gagne committed
740 741 742
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
743
        _settingsItem = NULL;
Don Gagne's avatar
Don Gagne committed
744 745
    }

746
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
747 748

    if (_visualItems->count() == 0) {
DonLakeFlyer's avatar
DonLakeFlyer committed
749
        _addMissionSettings(_visualItems, true /* addToCenter */);
Don Gagne's avatar
Don Gagne committed
750 751
    }

752
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
753

Don Gagne's avatar
Don Gagne committed
754
    _initAllVisualItems();
755
}
756

757 758 759 760 761 762
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

763
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788
        errorString = errorMessage.arg(errorStr);
        return false;
    }
    _initLoadedVisualItems(loadedVisualItems);

    return true;
}

bool MissionController::loadJsonFile(QFile& file, QString& errorString)
{
    QString         errorStr;
    QString         errorMessage = tr("Mission: %1");
    QJsonDocument   jsonDoc;
    QByteArray      bytes = file.readAll();

    if (!JsonHelper::isJsonFile(bytes, jsonDoc, errorStr)) {
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    QJsonObject json = jsonDoc.object();
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);
    if (!_loadItemsFromJson(json, loadedVisualItems, errorStr)) {
        errorString = errorMessage.arg(errorStr);
        return false;
789
    }
790

791 792 793 794 795 796 797 798 799 800 801 802 803
    _initLoadedVisualItems(loadedVisualItems);

    return true;
}

bool MissionController::loadTextFile(QFile& file, QString& errorString)
{
    QString     errorStr;
    QString     errorMessage = tr("Mission: %1");
    QByteArray  bytes = file.readAll();
    QTextStream stream(bytes);

    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);
804
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
805 806 807 808 809 810
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
811
    return true;
812 813
}

814
void MissionController::save(QJsonObject& json)
815
{
816
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
817

818
    // Mission settings
819

820 821 822 823 824 825 826 827
    MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
    if (!settingsItem) {
        qWarning() << "First item is not MissionSettingsItem";
        return;
    }
    QJsonValue coordinateValue;
    JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
    json[_jsonPlannedHomePositionKey] = coordinateValue;
828 829 830 831
    json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
832

833
    // Save the visual items
834

835 836 837
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
838

839 840
        visualItem->save(rgJsonMissionItems);
    }
841

842 843 844
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
845

846 847 848 849 850
        if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
851
        }
852 853
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
854 855 856
        }
    }

857
    json[_jsonItemsKey] = rgJsonMissionItems;
858 859
}

860
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
861
{
Don Gagne's avatar
Don Gagne committed
862
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
863
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
864 865 866 867
    bool            distanceOk =    false;

    // Convert to fixed altitudes

868
    distanceOk = true;
869
    if (currentItem->coordinateHasRelativeAltitude()) {
870 871
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
872
    if (prevItem->exitCoordinateHasRelativeAltitude()) {
873
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
874 875 876
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
877 878 879
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
880
    } else {
Don Gagne's avatar
Don Gagne committed
881
        *altDifference = 0.0;
882
        *azimuth = 0.0;
883
        *distance = 0.0;
884 885 886
    }
}

887
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
888 889 890 891 892 893 894
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

895
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
896 897
}

898 899
void MissionController::_recalcWaypointLines(void)
{
900 901 902
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

903
    bool showHomePosition = _settingsItem->coordinate().isValid();
904

905
    qCDebug(MissionControllerLog) << "_recalcWaypointLines showHomePosition" << showHomePosition;
906

Nate Weibley's avatar
Nate Weibley committed
907 908
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
909 910 911 912 913 914 915
    _waypointLines.clear();

    bool linkBackToHome = false;
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));


916
        // If we still haven't found the first coordinate item and we hit a takeoff command, link back to home
917 918
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
919 920
                (qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
                 qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
921 922 923 924 925 926 927
            linkBackToHome = true;
        }

        if (item->specifiesCoordinate()) {
            if (!item->isStandaloneCoordinate()) {
                firstCoordinateItem = false;
                VisualItemPair pair(lastCoordinateItem, item);
928
                if (lastCoordinateItem != _settingsItem || (showHomePosition && linkBackToHome)) {
929 930
                    if (old_table.contains(pair)) {
                        // Do nothing, this segment already exists and is wired up
Nate Weibley's avatar
Nate Weibley committed
931
                        _linesTable[pair] = old_table.take(pair);
932 933 934 935
                    } else {
                        // Create a new segment and wire update notifiers
                        auto linevect       = new CoordinateVector(lastCoordinateItem->isSimpleItem() ? lastCoordinateItem->coordinate() : lastCoordinateItem->exitCoordinate(), item->coordinate(), this);
                        auto originNotifier = lastCoordinateItem->isSimpleItem() ? &VisualMissionItem::coordinateChanged : &VisualMissionItem::exitCoordinateChanged,
Don Gagne's avatar
Don Gagne committed
936
                                endNotifier    = &VisualMissionItem::coordinateChanged;
937 938 939 940 941 942
                        // Use signals/slots to update the coordinate endpoints
                        connect(lastCoordinateItem, originNotifier, linevect, &CoordinateVector::setCoordinate1);
                        connect(item,               endNotifier,    linevect, &CoordinateVector::setCoordinate2);

                        // FIXME: We should ideally have signals for 2D position change, alt change, and 3D position change
                        // Not optimal, but still pretty fast, do a full update of range/bearing/altitudes
DonLakeFlyer's avatar
DonLakeFlyer committed
943
                        connect(item, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcMissionFlightStatus);
Nate Weibley's avatar
Nate Weibley committed
944
                        _linesTable[pair] = linevect;
945 946 947 948 949 950 951 952 953 954
                    }
                }
                lastCoordinateItem = item;
            }
        }
    }

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
955 956
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
957 958 959 960 961 962 963 964 965 966
            objs.append(vect);
        }

        // We don't delete here because many links may still be valid
        _waypointLines.swapObjectList(objs);
    }

    // Anything left in the old table is an obsolete line object that can go
    qDeleteAll(old_table);

DonLakeFlyer's avatar
DonLakeFlyer committed
967
    _recalcMissionFlightStatus();
968 969 970 971

    emit waypointLinesChanged();
}

972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001
void MissionController::_updateBatteryInfo(int waypointIndex)
{
    if (_missionFlightStatus.mAhBattery != 0) {
        _missionFlightStatus.hoverAmpsTotal = (_missionFlightStatus.hoverTime / 60.0) * _missionFlightStatus.hoverAmps;
        _missionFlightStatus.cruiseAmpsTotal = (_missionFlightStatus.cruiseTime / 60.0) * _missionFlightStatus.cruiseAmps;
        _missionFlightStatus.batteriesRequired = ceil((_missionFlightStatus.hoverAmpsTotal + _missionFlightStatus.cruiseAmpsTotal) / _missionFlightStatus.ampMinutesAvailable);
        if (_missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
            _missionFlightStatus.batteryChangePoint = waypointIndex - 1;
        }
    }
}

void MissionController::_addHoverTime(double hoverTime, double hoverDistance, int waypointIndex)
{
    _missionFlightStatus.totalTime += hoverTime;
    _missionFlightStatus.hoverTime += hoverTime;
    _missionFlightStatus.hoverDistance += hoverDistance;
    _missionFlightStatus.totalDistance += hoverDistance;
    _updateBatteryInfo(waypointIndex);
}

void MissionController::_addCruiseTime(double cruiseTime, double cruiseDistance, int waypointIndex)
{
    _missionFlightStatus.totalTime += cruiseTime;
    _missionFlightStatus.cruiseTime += cruiseTime;
    _missionFlightStatus.cruiseDistance += cruiseDistance;
    _missionFlightStatus.totalDistance += cruiseDistance;
    _updateBatteryInfo(waypointIndex);
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1002
void MissionController::_recalcMissionFlightStatus()
1003
{
1004
    if (!_visualItems->count()) {
1005
        return;
1006
    }
1007 1008 1009 1010

    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

1011
    bool showHomePosition = _settingsItem->coordinate().isValid();
1012

DonLakeFlyer's avatar
DonLakeFlyer committed
1013
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1014

1015 1016 1017
    // If home position is valid we can calculate distances between all waypoints.
    // If home position is not valid we can only calculate distances between waypoints which are
    // both relative altitude.
1018

1019
    // No values for first item
1020
    lastCoordinateItem->setAltDifference(0.0);
1021
    lastCoordinateItem->setAzimuth(0.0);
1022
    lastCoordinateItem->setDistance(0.0);
1023

1024 1025
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1026 1027
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1028

1029
    _resetMissionFlightStatus();
1030

DonLakeFlyer's avatar
DonLakeFlyer committed
1031
    bool vtolInHover = true;
Don Gagne's avatar
Don Gagne committed
1032
    bool linkBackToHome = false;
1033

DonLakeFlyer's avatar
DonLakeFlyer committed
1034
    for (int i=0; i<_visualItems->count(); i++) {
1035
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1036 1037 1038
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1039 1040
        // Assume the worst
        item->setAzimuth(0.0);
1041
        item->setDistance(0.0);
1042

DonLakeFlyer's avatar
DonLakeFlyer committed
1043 1044 1045
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1046
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1047
                _missionFlightStatus.hoverSpeed = newSpeed;
1048
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1049 1050
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1051
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1052
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1053
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1054 1055
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1056
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1057 1058 1059 1060
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1061
        if (_managerVehicle->vehicleYawsToNextWaypointInMission()) {
1062 1063 1064 1065 1066
            // We current only support gimbal display in this mode
            double gimbalYaw = item->specifiedGimbalYaw();
            if (!qIsNaN(gimbalYaw)) {
                _missionFlightStatus.gimbalYaw = gimbalYaw;
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1067 1068 1069 1070 1071
        }

        if (i == 0) {
            // We only process speed and gimbal from Mission Settings item
            continue;
1072 1073
        }

1074 1075 1076 1077 1078 1079 1080 1081
        // Link back to home if first item is takeoff and we have home position
        if (firstCoordinateItem && simpleItem && simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
            if (showHomePosition) {
                linkBackToHome = true;
            }
        }

        // Update VTOL state
1082
        if (simpleItem && _controllerVehicle->vtol()) {
1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096
            switch (simpleItem->command()) {
            case MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF:
                vtolInHover = false;
                break;
            case MavlinkQmlSingleton::MAV_CMD_NAV_LAND:
                vtolInHover = false;
                break;
            case MavlinkQmlSingleton::MAV_CMD_DO_VTOL_TRANSITION:
            {
                int transitionState = simpleItem->missionItem().param1();
                if (transitionState == MAV_VTOL_STATE_TRANSITION_TO_MC) {
                    vtolInHover = true;
                } else if (transitionState == MAV_VTOL_STATE_TRANSITION_TO_FW) {
                    vtolInHover = false;
1097 1098
                }
            }
1099 1100 1101
                break;
            default:
                break;
1102
            }
Don Gagne's avatar
Don Gagne committed
1103 1104
        }

1105
        if (item->specifiesCoordinate()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1106 1107
            // Update vehicle yaw assuming direction to next waypoint
            if (item != lastCoordinateItem) {
1108 1109
                _missionFlightStatus.vehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
                lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
DonLakeFlyer's avatar
DonLakeFlyer committed
1110 1111
            }

1112 1113
            // Keep track of the min/max altitude for all waypoints so we can show altitudes as a percentage

1114
            double absoluteAltitude = item->coordinate().altitude();
1115
            if (item->coordinateHasRelativeAltitude()) {
1116 1117 1118 1119 1120
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1121 1122 1123 1124 1125 1126 1127 1128 1129 1130
            if (!item->exitCoordinateSameAsEntry()) {
                absoluteAltitude = item->exitCoordinate().altitude();
                if (item->exitCoordinateHasRelativeAltitude()) {
                    absoluteAltitude += homePositionAltitude;
                }
                minAltSeen = std::min(minAltSeen, absoluteAltitude);
                maxAltSeen = std::max(maxAltSeen, absoluteAltitude);
            }

            if (!item->isStandaloneCoordinate()) {
Don Gagne's avatar
Don Gagne committed
1131
                firstCoordinateItem = false;
1132
                if (lastCoordinateItem != _settingsItem || linkBackToHome) {
1133 1134
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1135

1136
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1137 1138 1139
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1140

1141
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1142

DonLakeFlyer's avatar
DonLakeFlyer committed
1143 1144 1145
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1146
                    if (_controllerVehicle->vtol()) {
1147
                        if (vtolInHover) {
1148
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
1149
                        } else {
1150
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
1151 1152
                        }
                    } else {
1153
                        if (_controllerVehicle->multiRotor()) {
1154
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1155
                        } else {
1156
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1157
                        }
1158
                    }
1159
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1160

1161
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1162 1163
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1164
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1165

1166 1167
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1168
                    if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1169
                        if (vtolInHover) {
1170
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1171
                        } else {
1172
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1173 1174
                        }
                    } else {
1175
                        if (_controllerVehicle->multiRotor()) {
1176
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1177
                        } else {
1178
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1179 1180
                        }
                    }
1181
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1182 1183

                item->setMissionFlightStatus(_missionFlightStatus);
1184
            }
1185 1186

            lastCoordinateItem = item;
1187 1188
        }
    }
1189
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1190

1191 1192 1193
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1194

DonLakeFlyer's avatar
DonLakeFlyer committed
1195 1196 1197 1198 1199 1200 1201
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1202 1203
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1204

1205 1206
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1207 1208
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1209 1210 1211

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1212
            if (item->coordinateHasRelativeAltitude()) {
1213 1214 1215 1216 1217 1218
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1219
            }
1220 1221 1222 1223
        }
    }
}

1224 1225 1226
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1227 1228 1229 1230 1231 1232
    // Setup ascending sequence numbers for all visual items

    int sequenceNumber = 0;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));

1233 1234
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1235 1236 1237
    }
}

1238 1239 1240
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1241
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1242 1243 1244

    currentParentItem->childItems()->clear();

1245 1246
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1247 1248 1249 1250 1251

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1252
        } else if (item->isSimpleItem()) {
1253 1254 1255 1256 1257
            currentParentItem->childItems()->append(item);
        }
    }
}

1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273 1274
void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
{
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

    // Set the planned home position to be a deltae from first coordinate
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

        if (item->specifiesCoordinate()) {
            _settingsItem->setCoordinate(item->coordinate().atDistanceAndAzimuth(30, 0));
        }
    }
}


1275 1276
void MissionController::_recalcAll(void)
{
1277 1278 1279
    if (_editMode) {
        _setPlannedHomePositionFromFirstCoordinate();
    }
1280
    _recalcSequence();
1281 1282 1283 1284
    _recalcChildItems();
    _recalcWaypointLines();
}

1285
/// Initializes a new set of mission items
1286
void MissionController::_initAllVisualItems(void)
1287
{
1288 1289
    // Setup home position at index 0

1290 1291 1292
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1293 1294
        return;
    }
1295 1296 1297
    if (_editMode) {
        _settingsItem->setIsCurrentItem(true);
    }
1298

Don Gagne's avatar
Don Gagne committed
1299 1300
    if (!_editMode && _managerVehicle->homePosition().isValid()) {
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1301
    }
1302

1303
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
1304
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);
1305

1306 1307 1308 1309
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1310

1311
    _recalcAll();
1312

1313
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1314 1315 1316
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1317
    emit containsItemsChanged(containsItems());
1318
    emit plannedHomePositionChanged(plannedHomePosition());
1319

1320
    setDirty(false);
1321 1322
}

1323
void MissionController::_deinitAllVisualItems(void)
1324
{
1325 1326 1327
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1328 1329
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1330 1331
    }

1332
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1333
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1334 1335
}

1336
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1337
{
1338
    setDirty(false);
1339

1340
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1341 1342
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1343 1344
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1345
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1346

1347 1348 1349 1350 1351 1352 1353 1354
    if (visualItem->isSimpleItem()) {
        // We need to track commandChanged on simple item since recalc has special handling for takeoff command
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
        if (simpleItem) {
            connect(&simpleItem->missionItem()._commandFact, &Fact::valueChanged, this, &MissionController::_itemCommandChanged);
        } else {
            qWarning() << "isSimpleItem == true, yet not SimpleMissionItem";
        }
1355 1356
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1357
        if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1358
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcMissionFlightStatus);
1359 1360 1361
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1362
    }
1363 1364
}

1365
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1366
{
1367 1368
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1369 1370
}

1371
void MissionController::_itemCommandChanged(void)
1372
{
1373 1374
    _recalcChildItems();
    _recalcWaypointLines();
1375 1376
}

1377
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1378
{
1379 1380 1381 1382 1383 1384
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1385

1386 1387
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1388
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1389 1390
        return;
    }
1391

1392 1393
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1394 1395
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1396 1397 1398 1399 1400 1401 1402 1403 1404
    connect(_missionManager, &MissionManager::inProgressChanged,        this, &MissionController::_inProgressChanged);
    connect(_missionManager, &MissionManager::progressPct,              this, &MissionController::_progressPctChanged);
    connect(_missionManager, &MissionManager::currentIndexChanged,      this, &MissionController::_currentMissionIndexChanged);
    connect(_missionManager, &MissionManager::lastCurrentIndexChanged,  this, &MissionController::resumeMissionIndexChanged);
    connect(_missionManager, &MissionManager::resumeMissionReady,       this, &MissionController::resumeMissionReady);
    connect(_managerVehicle, &Vehicle::homePositionChanged,             this, &MissionController::_managerVehicleHomePositionChanged);
    connect(_managerVehicle, &Vehicle::defaultCruiseSpeedChanged,       this, &MissionController::_recalcMissionFlightStatus);
    connect(_managerVehicle, &Vehicle::defaultHoverSpeedChanged,        this, &MissionController::_recalcMissionFlightStatus);
    connect(_managerVehicle, &Vehicle::vehicleTypeChanged,              this, &MissionController::complexMissionItemNamesChanged);
1405

1406 1407
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1408
    }
1409

1410
    emit complexMissionItemNamesChanged();
1411
    emit resumeMissionIndexChanged();
1412 1413
}

1414
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1415
{
1416 1417
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1418
        if (settingsItem) {
1419
            settingsItem->setCoordinate(homePosition);
1420
        } else {
1421
            qWarning() << "First item is not MissionSettingsItem";
1422
        }
1423 1424 1425 1426
        if (_visualItems->count() == 1) {
            // Don't let this trip the dirty bit
            _visualItems->setDirty(false);
        }
1427
    }
1428 1429 1430
}

void MissionController::_inProgressChanged(bool inProgress)
1431
{
1432
    emit syncInProgressChanged(inProgress);
1433
}
1434

1435
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1436
{
1437 1438 1439
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1440

1441 1442 1443 1444 1445 1446
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

    for (int i=newIndex; i>0; i--) {
1447
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1448

1449 1450 1451
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1452
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1453 1454 1455
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1456
                    break;
1457 1458
                }
            }
1459 1460 1461
        }
    }

1462
    if (found) {
1463 1464
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1465 1466 1467
    }

    return found;
1468
}
1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481

double MissionController::_normalizeLat(double lat)
{
    // Normalize latitude to range: 0 to 180, S to N
    return lat + 90.0;
}

double MissionController::_normalizeLon(double lon)
{
    // Normalize longitude to range: 0 to 360, W to E
    return lon  + 180.0;
}

1482
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1483
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1484
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1485
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
1486

Don Gagne's avatar
Don Gagne committed
1487 1488
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1489
    visualItems->insert(0, settingsItem);
1490

1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515
    if (addToCenter) {
        if (visualItems->count() > 1) {
            double north = 0.0;
            double south = 0.0;
            double east  = 0.0;
            double west  = 0.0;
            bool firstCoordSet = false;

            for (int i=1; i<visualItems->count(); i++) {
                VisualMissionItem* item = qobject_cast<VisualMissionItem*>(visualItems->get(i));
                if (item->specifiesCoordinate()) {
                    if (firstCoordSet) {
                        double lat = _normalizeLat(item->coordinate().latitude());
                        double lon = _normalizeLon(item->coordinate().longitude());
                        north = fmax(north, lat);
                        south = fmin(south, lat);
                        east  = fmax(east, lon);
                        west  = fmin(west, lon);
                    } else {
                        firstCoordSet = true;
                        north = _normalizeLat(item->coordinate().latitude());
                        south = north;
                        east  = _normalizeLon(item->coordinate().longitude());
                        west  = east;
                    }
1516 1517
                }
            }
1518

1519 1520 1521
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1522
        }
Don Gagne's avatar
Don Gagne committed
1523 1524
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1525 1526
    }
}
1527

1528
int MissionController::resumeMissionIndex(void) const
1529
{
1530

1531
    int resumeIndex = 0;
1532

1533
    if (!_editMode) {
1534
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1535
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1536 1537
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1538 1539
        } else {
            resumeIndex = 0;
1540 1541 1542 1543 1544
        }
    }

    return resumeIndex;
}
1545

1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558
int MissionController::currentMissionIndex(void) const
{
    if (_editMode) {
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1559
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1560 1561
{
    if (!_editMode) {
1562
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1563 1564 1565
            sequenceNumber++;
        }

1566 1567
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1568 1569
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1570
        emit currentMissionIndexChanged(currentMissionIndex());
1571 1572
    }
}
1573

1574
bool MissionController::syncInProgress(void) const
1575
{
1576
    return _missionManager->inProgress();
1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588
}

bool MissionController::dirty(void) const
{
    return _visualItems ? _visualItems->dirty() : false;
}


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1589
    }
1590
}
1591

1592 1593
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1594 1595 1596
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, vehicle);

1597 1598 1599 1600 1601 1602
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

        qCDebug(MissionControllerLog) << "MissionController::_scanForAdditionalSettings count:scanIndex" << visualItems->count() << scanIndex;

1603
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
1604 1605 1606
        if (settingsItem) {
            scanIndex++;
            settingsItem->scanForMissionSettings(visualItems, scanIndex);
1607 1608 1609 1610
            continue;
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1611
        if (simpleItem) {
1612 1613 1614 1615 1616
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1617 1618 1619
        }
    }
}
1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632

void MissionController::_updateContainsItems(void)
{
    emit containsItemsChanged(containsItems());
}

bool MissionController::containsItems(void) const
{
    return _visualItems ? _visualItems->count() > 1 : false;
}

void MissionController::removeAllFromVehicle(void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1633 1634 1635 1636 1637 1638 1639 1640
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::removeAllFromVehicle called while offline";
    } else if (syncInProgress()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::removeAllFromVehicle called while syncInProgress";
    } else {
        _itemsRequested = true;
        _missionManager->removeAll();
    }
1641
}
1642 1643 1644 1645 1646 1647

QStringList MissionController::complexMissionItemNames(void) const
{
    QStringList complexItems;

    complexItems.append(_surveyMissionItemName);
1648
    if (_controllerVehicle->fixedWing()) {
1649 1650 1651 1652 1653
        complexItems.append(_fwLandingMissionItemName);
    }

    return complexItems;
}
1654

1655 1656
void MissionController::resumeMission(int resumeIndex)
{
1657
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1658 1659
        resumeIndex--;
    }
1660
    _missionManager->generateResumeMission(resumeIndex);
1661
}
1662 1663 1664 1665 1666 1667 1668 1669 1670

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1671 1672 1673 1674 1675 1676 1677 1678 1679 1680

void MissionController::applyDefaultMissionAltitude(void)
{
    double defaultAltitude = _appSettings->defaultMissionItemAltitude()->rawValue().toDouble();

    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);
        item->applyNewAltitude(defaultAltitude);
    }
}
1681

1682 1683 1684 1685 1686 1687 1688
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
1689 1690 1691 1692 1693 1694

void MissionController::_visualItemsDirtyChanged(bool dirty)
{
    // We could connect signal to signal and not need this but this is handy for setting a breakpoint on
    emit dirtyChanged(dirty);
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1695 1696 1697

bool MissionController::showPlanFromManagerVehicle (void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1698
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle" << _editMode;
DonLakeFlyer's avatar
DonLakeFlyer committed
1699 1700
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
1701
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716 1717 1718 1719 1720
    } else {
        if (!_managerVehicle->initialPlanRequestComplete()) {
            // The vehicle hasn't completed initial load, we can just wait for newMissionItemsAvailable to be signalled automatically
            qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle: !initialPlanRequestComplete, wait for signal";
            return true;
        } else if (syncInProgress()) {
            // If the sync is already in progress, newMissionItemsAvailable will be signalled automatically when it is done. So no need to do anything.
            qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle: syncInProgress wait for signal";
            return true;
        } else {
            // Fake a _newMissionItemsAvailable with the current items
            qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle: sync complete simulate signal";
            _itemsRequested = true;
            _newMissionItemsAvailableFromVehicle(false /* removeAllRequested */);
            return false;
        }
    }
}

1721
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1722
{
1723 1724
    // Fly view always reloads on send complete
    if (!error && !_editMode) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1725 1726 1727 1728
        showPlanFromManagerVehicle();
    }
}

1729
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1730
{
1731 1732 1733 1734
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1735
}