MissionController.cc 73 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
            if (!settingsItem) {
                qWarning() << "First item is not settings item";
                return;
            }
161 162 163 164
            MissionItem* fakeHomeItem = newMissionItems[0];
            if (fakeHomeItem->coordinate().latitude() != 0 || fakeHomeItem->coordinate().longitude() != 0) {
                settingsItem->setCoordinate(fakeHomeItem->coordinate());
            }
165 166
            i = 1;
        }
167

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

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

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

184
        if (_editMode) {
185
            MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
186
        }
187

188
        _initAllVisualItems();
189
        _updateContainsItems();
190
        emit newItemsFromVehicle();
191
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
192
    _itemsRequested = false;
193 194
}

195
void MissionController::loadFromVehicle(void)
196
{
DonLakeFlyer's avatar
DonLakeFlyer committed
197 198 199 200 201 202 203 204
    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();
    }
205 206
}

207
void MissionController::sendToVehicle(void)
208
{
DonLakeFlyer's avatar
DonLakeFlyer committed
209 210 211 212 213
    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
214
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
DonLakeFlyer's avatar
DonLakeFlyer committed
215 216 217 218 219 220 221 222 223
        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
224 225
}

226 227 228 229 230
/// 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
231 232 233 234
    if (visualMissionItems->count() == 0) {
        return false;
    }

235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250
    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
251
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
252 253 254 255 256 257 258
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

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

264
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
265

266
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
267

268 269
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
270
        }
271 272
    }
}
273

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

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

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

    _recalcAll();

310
    return newItem->sequenceNumber();
311 312
}

313
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
314
{
315 316
    ComplexMissionItem* newItem;

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

349
    _visualItems->insert(i, newItem);
350 351 352

    _recalcAll();

353
    return newItem->sequenceNumber();
354 355
}

356 357
void MissionController::removeMissionItem(int index)
{
358 359 360 361 362 363
    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);
364
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
365

366
    _deinitVisualItem(item);
367
    item->deleteLater();
368

369 370 371 372 373 374 375 376 377 378
    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;
            }
        }

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

397
    _recalcAll();
398
    setDirty(true);
399 400
}

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

415
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
416 417 418 419 420 421 422 423 424
{
    // 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)) {
425 426 427
        return false;
    }

428
    // Read complex items
429
    QList<SurveyMissionItem*> surveyItems;
430 431 432 433
    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];
434

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

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

449 450 451 452 453
    // 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
454
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
455

456
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
457 458 459 460
    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
461 462
        if (nextComplexItemIndex < surveyItems.count()) {
            SurveyMissionItem* complexItem = surveyItems[nextComplexItemIndex];
463 464 465 466 467 468 469 470 471 472 473 474 475 476

            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++];

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

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

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

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

    return true;
}

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

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

529
    // Mission Settings
530
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
531

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

546 547 548 549 550
    QGeoCoordinate homeCoordinate;
    if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
        return false;
    }
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
551 552
    settingsItem->setCoordinate(homeCoordinate);
    visualItems->insert(0, settingsItem);
Don Gagne's avatar
Don Gagne committed
553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578
    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) {
579
            SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, visualItems);
580
            if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
581
                qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
582
                nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
Don Gagne's avatar
Don Gagne committed
583 584 585 586 587 588 589 590 591 592 593 594 595 596 597
                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;
598
                SurveyMissionItem* surveyItem = new SurveyMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
599 600 601 602 603 604
                if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(surveyItem);
605
            } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
606
                qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
607
                FixedWingLandingComplexItem* landingItem = new FixedWingLandingComplexItem(_controllerVehicle, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
608 609 610 611 612 613
                if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
                    return false;
                }
                nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
                qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
                visualItems->append(landingItem);
614
            } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
DonLakeFlyer's avatar
DonLakeFlyer committed
615
                qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
616
                MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
DonLakeFlyer's avatar
DonLakeFlyer committed
617 618 619 620 621 622
                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
623 624 625 626 627 628 629 630 631 632 633 634 635
            } 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
636
            if ((MAV_CMD)doJumpItem->command() == MAV_CMD_DO_JUMP) {
Don Gagne's avatar
Don Gagne committed
637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659
                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;
}

660 661 662 663 664 665 666 667
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;
668 669 670 671 672 673
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
674 675

    if (fileVersion == 1) {
676
        return _loadJsonMissionFileV1(json, visualItems, errorString);
677
    } else {
678
        return _loadJsonMissionFileV2(json, visualItems, errorString);
679 680 681
    }
}

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

    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;
695
            plannedHomePositionInFile = true;
696 697 698
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
699
            plannedHomePositionInFile = false;
700 701 702 703
        }
    }

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

708
        while (!stream.atEnd()) {
709
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
710 711

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

728
    if (!plannedHomePositionInFile) {
729 730 731 732 733
        // 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
734 735
            }
        }
736 737 738
    }

    return true;
739 740
}

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

749
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
750 751

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

755
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
756

Don Gagne's avatar
Don Gagne committed
757
    _initAllVisualItems();
758
}
759

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

766
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791
        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;
792
    }
793

794 795 796 797 798 799 800 801 802 803 804 805 806
    _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);
807
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
808 809 810 811 812 813
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
814
    return true;
815 816
}

817
void MissionController::save(QJsonObject& json)
818
{
819
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
820

821
    // Mission settings
822

823 824 825 826 827 828 829 830
    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;
831 832 833 834
    json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
835

836
    // Save the visual items
837

838 839 840
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
841

842 843
        visualItem->save(rgJsonMissionItems);
    }
844

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

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

860
    json[_jsonItemsKey] = rgJsonMissionItems;
861 862
}

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

    // Convert to fixed altitudes

871
    distanceOk = true;
872
    if (currentItem != _settingsItem && currentItem->coordinateHasRelativeAltitude()) {
873 874
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
875
    if (prevItem != _settingsItem && prevItem->exitCoordinateHasRelativeAltitude()) {
876
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
877 878 879
    }

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

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

    distanceOk = true;

898
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
899 900
}

901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922
void MissionController::_addWaypointLineSegment(CoordVectHashTable& prevItemPairHashTable, VisualItemPair& pair)
{
    if (prevItemPairHashTable.contains(pair)) {
        // Pair already exists and connected, just re-use
        _linesTable[pair] = prevItemPairHashTable.take(pair);
    } else {
        // Create a new segment and wire update notifiers
        auto linevect       = new CoordinateVector(pair.first->isSimpleItem() ? pair.first->coordinate() : pair.first->exitCoordinate(), pair.second->coordinate(), this);
        auto originNotifier = pair.first->isSimpleItem() ? &VisualMissionItem::coordinateChanged : &VisualMissionItem::exitCoordinateChanged;
        auto endNotifier    = &VisualMissionItem::coordinateChanged;

        // Use signals/slots to update the coordinate endpoints
        connect(pair.first,     originNotifier, linevect, &CoordinateVector::setCoordinate1);
        connect(pair.second,    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
        connect(pair.second, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcMissionFlightStatus);
        _linesTable[pair] = linevect;
    }
}

923 924
void MissionController::_recalcWaypointLines(void)
{
925 926 927
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

928
    bool showHomePosition = _settingsItem->coordinate().isValid();
929

930
    qCDebug(MissionControllerLog) << "_recalcWaypointLines showHomePosition" << showHomePosition;
931

Nate Weibley's avatar
Nate Weibley committed
932 933
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
934 935
    _waypointLines.clear();

936 937 938 939 940 941 942 943 944
    bool linkEndToHome;
    SimpleMissionItem* lastItem = _visualItems->value<SimpleMissionItem*>(_visualItems->count() - 1);
    if (lastItem && (int)lastItem->command() == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
        linkEndToHome = true;
    } else {
        linkEndToHome = _settingsItem->missionEndRTL();
    }

    bool linkStartToHome = false;
945 946 947 948
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));


949
        // If we still haven't found the first coordinate item and we hit a takeoff command, link back to home
950 951
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
952 953
                (qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
                 qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
954
            linkStartToHome = true;
955 956 957 958 959 960
        }

        if (item->specifiesCoordinate()) {
            if (!item->isStandaloneCoordinate()) {
                firstCoordinateItem = false;
                VisualItemPair pair(lastCoordinateItem, item);
961 962
                if (lastCoordinateItem != _settingsItem || (showHomePosition && linkStartToHome)) {
                    _addWaypointLineSegment(old_table, pair);
963 964 965 966 967
                }
                lastCoordinateItem = item;
            }
        }
    }
968 969 970 971
    if (linkEndToHome && lastCoordinateItem != _settingsItem && showHomePosition) {
        VisualItemPair pair(lastCoordinateItem, _settingsItem);
        _addWaypointLineSegment(old_table, pair);
    }
972 973 974 975

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
976 977
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
978 979 980 981 982 983 984 985 986 987
            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
988
    _recalcMissionFlightStatus();
989 990 991 992

    emit waypointLinesChanged();
}

993 994 995 996 997 998
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);
999
        if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022
            _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);
}

1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069
/// Adds additional time to a mission as specified by the command
void MissionController::_addCommandTimeDelay(SimpleMissionItem* simpleItem, bool vtolInHover)
{
    double seconds = 0;

    if (!simpleItem) {
        return;
    }

    // This routine is currently quite minimal and only handles the simple cases.
    switch ((int)simpleItem->command()) {
    case MAV_CMD_NAV_WAYPOINT:
    case MAV_CMD_CONDITION_DELAY:
        seconds = simpleItem->missionItem().param1();
        break;
    }

    _addTimeDistance(vtolInHover, 0, 0, seconds, 0, -1);
}

/// Adds the specified time to the appropriate hover or cruise time values.
///     @param vtolInHover true: vtol is currrent in hover mode
///     @param hoverTime    Amount of time tp add to hover
///     @param cruiseTime   Amount of time to add to cruise
///     @param extraTime    Amount of additional time to add to hover/cruise
///     @param seqNum       Sequence number of waypoint for these values, -1 for no waypoint associated
void MissionController::_addTimeDistance(bool vtolInHover, double hoverTime, double cruiseTime, double extraTime, double distance, int seqNum)
{
    if (_controllerVehicle->vtol()) {
        if (vtolInHover) {
            _addHoverTime(hoverTime, distance, seqNum);
            _addHoverTime(extraTime, 0, -1);
        } else {
            _addCruiseTime(cruiseTime, distance, seqNum);
            _addCruiseTime(extraTime, 0, -1);
        }
    } else {
        if (_controllerVehicle->multiRotor()) {
            _addHoverTime(hoverTime, distance, seqNum);
            _addHoverTime(extraTime, 0, -1);
        } else {
            _addCruiseTime(cruiseTime, distance, seqNum);
            _addCruiseTime(extraTime, 0, -1);
        }
    }
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1070
void MissionController::_recalcMissionFlightStatus()
1071
{
1072
    if (!_visualItems->count()) {
1073
        return;
1074
    }
1075 1076 1077 1078

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

1079
    bool showHomePosition = _settingsItem->coordinate().isValid();
1080

DonLakeFlyer's avatar
DonLakeFlyer committed
1081
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1082

1083 1084 1085
    // 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.
1086

1087
    // No values for first item
1088
    lastCoordinateItem->setAltDifference(0.0);
1089
    lastCoordinateItem->setAzimuth(0.0);
1090
    lastCoordinateItem->setDistance(0.0);
1091

1092 1093
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1094 1095
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1096

1097
    _resetMissionFlightStatus();
1098

DonLakeFlyer's avatar
DonLakeFlyer committed
1099
    bool vtolInHover = true;
1100
    bool linkStartToHome = false;
1101 1102 1103 1104 1105 1106 1107 1108 1109 1110
    bool linkEndToHome = false;

    if (showHomePosition) {
        SimpleMissionItem* lastItem = _visualItems->value<SimpleMissionItem*>(_visualItems->count() - 1);
        if (lastItem && (int)lastItem->command() == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
            linkEndToHome = true;
        } else {
            linkEndToHome = _settingsItem->missionEndRTL();
        }
    }
1111

DonLakeFlyer's avatar
DonLakeFlyer committed
1112
    for (int i=0; i<_visualItems->count(); i++) {
1113
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1114 1115 1116
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1117 1118
        // Assume the worst
        item->setAzimuth(0.0);
1119
        item->setDistance(0.0);
1120

DonLakeFlyer's avatar
DonLakeFlyer committed
1121 1122 1123
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1124
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1125
                _missionFlightStatus.hoverSpeed = newSpeed;
1126
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1127 1128
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1129
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1130
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1131
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1132 1133
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1134
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1135 1136 1137 1138
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1139
        if (_managerVehicle->vehicleYawsToNextWaypointInMission()) {
1140 1141 1142 1143 1144
            // We current only support gimbal display in this mode
            double gimbalYaw = item->specifiedGimbalYaw();
            if (!qIsNaN(gimbalYaw)) {
                _missionFlightStatus.gimbalYaw = gimbalYaw;
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1145 1146 1147 1148 1149
        }

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

1152 1153 1154
        // 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) {
1155
                linkStartToHome = true;
1156 1157 1158 1159 1160 1161 1162
                if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
                    // We have to special case takeoff, assuming vehicle takes off straight up to specified altitude
                    double azimuth, distance, altDifference;
                    _calcPrevWaypointValues(homePositionAltitude, _settingsItem, simpleItem, &azimuth, &distance, &altDifference);
                    double takeoffTime = qAbs(altDifference) / _appSettings->offlineEditingAscentSpeed()->rawValue().toDouble();
                    _addHoverTime(takeoffTime, 0, -1);
                }
1163 1164 1165 1166
            }
        }

        // Update VTOL state
1167
        if (simpleItem && _controllerVehicle->vtol()) {
1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181
            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;
1182 1183
                }
            }
1184 1185 1186
                break;
            default:
                break;
1187
            }
Don Gagne's avatar
Don Gagne committed
1188 1189
        }

1190 1191 1192
        // Check for command specific time delays
        _addCommandTimeDelay(simpleItem, vtolInHover);

1193
        if (item->specifiesCoordinate()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1194 1195
            // Update vehicle yaw assuming direction to next waypoint
            if (item != lastCoordinateItem) {
1196 1197
                _missionFlightStatus.vehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
                lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
DonLakeFlyer's avatar
DonLakeFlyer committed
1198 1199
            }

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

1202
            double absoluteAltitude = item->coordinate().altitude();
1203
            if (item->coordinateHasRelativeAltitude()) {
1204 1205 1206 1207 1208
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1209 1210 1211 1212 1213 1214 1215 1216 1217 1218
            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
1219
                firstCoordinateItem = false;
1220
                if (lastCoordinateItem != _settingsItem || linkStartToHome) {
1221 1222
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1223

1224
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1225 1226 1227
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1228

1229
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1230

DonLakeFlyer's avatar
DonLakeFlyer committed
1231 1232 1233
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1234
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1235
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1236

1237
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1238 1239
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1240
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1241

1242 1243
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1244 1245
                    double extraTime = complexItem->additionalTimeDelay();
                    _addTimeDistance(vtolInHover, hoverTime, cruiseTime, extraTime, distance, item->sequenceNumber());
1246
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1247 1248

                item->setMissionFlightStatus(_missionFlightStatus);
1249
            }
1250 1251

            lastCoordinateItem = item;
1252 1253
        }
    }
1254
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1255

1256 1257 1258 1259 1260 1261 1262 1263
    if (linkEndToHome && lastCoordinateItem != _settingsItem) {
        double azimuth, distance, altDifference;
        _calcPrevWaypointValues(homePositionAltitude, lastCoordinateItem, _settingsItem, &azimuth, &distance, &altDifference);

        // Calculate time/distance
        double hoverTime = distance / _missionFlightStatus.hoverSpeed;
        double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
        double landTime = qAbs(altDifference) / _appSettings->offlineEditingDescentSpeed()->rawValue().toDouble();
1264
        _addTimeDistance(vtolInHover, hoverTime, cruiseTime, distance, landTime, -1);
1265 1266
    }

1267 1268 1269
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1270

DonLakeFlyer's avatar
DonLakeFlyer committed
1271 1272 1273 1274 1275 1276 1277
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1278 1279
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1280

1281 1282
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1283 1284
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1285 1286 1287

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1288
            if (item->coordinateHasRelativeAltitude()) {
1289 1290 1291 1292 1293 1294
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1295
            }
1296 1297 1298 1299
        }
    }
}

1300 1301 1302
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1303 1304 1305 1306 1307 1308
    // 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));

1309 1310
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1311 1312 1313
    }
}

1314 1315 1316
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1317
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1318 1319 1320

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

1321 1322
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1323 1324 1325 1326 1327

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1328
        } else if (item->isSimpleItem()) {
1329 1330 1331 1332 1333
            currentParentItem->childItems()->append(item);
        }
    }
}

1334 1335 1336 1337 1338 1339
void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
{
    if (_settingsItem->coordinate().isValid()) {
        return;
    }

1340
    // Set the planned home position to be a delta from first coordinate
1341 1342 1343 1344 1345 1346 1347 1348 1349 1350
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);

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


1351 1352
void MissionController::_recalcAll(void)
{
1353 1354 1355
    if (_editMode) {
        _setPlannedHomePositionFromFirstCoordinate();
    }
1356
    _recalcSequence();
1357 1358 1359 1360
    _recalcChildItems();
    _recalcWaypointLines();
}

1361
/// Initializes a new set of mission items
1362
void MissionController::_initAllVisualItems(void)
1363
{
1364 1365
    // Setup home position at index 0

1366 1367 1368
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1369 1370
        return;
    }
1371 1372 1373
    if (_editMode) {
        _settingsItem->setIsCurrentItem(true);
    }
1374

1375
    if (_managerVehicle->homePosition().isValid()) {
Don Gagne's avatar
Don Gagne committed
1376
        _settingsItem->setCoordinate(_managerVehicle->homePosition());
1377
    }
1378

1379 1380 1381
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged,  this, &MissionController::_recalcAll);
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged,     this, &MissionController::plannedHomePositionChanged);
1382

1383 1384 1385 1386
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1387

1388
    _recalcAll();
1389

1390
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1391 1392 1393
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1394
    emit containsItemsChanged(containsItems());
1395
    emit plannedHomePositionChanged(plannedHomePosition());
1396

1397
    setDirty(false);
1398 1399
}

1400
void MissionController::_deinitAllVisualItems(void)
1401
{
1402 1403 1404
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1405 1406
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1407 1408
    }

1409
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1410
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1411 1412
}

1413
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1414
{
1415
    setDirty(false);
1416

1417
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1418 1419
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1420 1421
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1422
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1423

1424 1425 1426 1427 1428 1429 1430 1431
    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";
        }
1432 1433
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1434
        if (complexItem) {
1435 1436
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged,       this, &MissionController::_recalcMissionFlightStatus);
            connect(complexItem, &ComplexMissionItem::additionalTimeDelayChanged,   this, &MissionController::_recalcMissionFlightStatus);
1437 1438 1439
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1440
    }
1441 1442
}

1443
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1444
{
1445 1446
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1447 1448
}

1449
void MissionController::_itemCommandChanged(void)
1450
{
1451 1452
    _recalcChildItems();
    _recalcWaypointLines();
1453 1454
}

1455
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1456
{
1457 1458 1459 1460 1461 1462
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1463

1464 1465
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1466
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1467 1468
        return;
    }
1469

1470 1471
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1472 1473
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1474 1475 1476 1477 1478
    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);
1479
    connect(_missionManager, &MissionManager::resumeMissionUploadFail,  this, &MissionController::resumeMissionUploadFail);
1480 1481 1482 1483
    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);
1484

1485 1486
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1487
    }
1488

1489
    emit complexMissionItemNamesChanged();
1490
    emit resumeMissionIndexChanged();
1491 1492
}

1493
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1494
{
1495 1496
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1497
        if (settingsItem) {
1498
            settingsItem->setCoordinate(homePosition);
1499
        } else {
1500
            qWarning() << "First item is not MissionSettingsItem";
1501
        }
1502 1503 1504
        // Don't let this trip the dirty bit. Otherwise plan will keep getting marked dirty if vehicle home
        // changes.
        _visualItems->setDirty(false);
1505
    }
1506 1507 1508
}

void MissionController::_inProgressChanged(bool inProgress)
1509
{
1510
    emit syncInProgressChanged(inProgress);
1511
}
1512

1513
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1514
{
1515 1516 1517
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1518

1519 1520 1521 1522 1523 1524
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1527 1528 1529
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1530
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1531 1532 1533
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1534
                    break;
1535 1536
                }
            }
1537 1538 1539
        }
    }

1540
    if (found) {
1541 1542
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1543 1544 1545
    }

    return found;
1546
}
1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559

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

1560
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1561
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1562
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1563
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
1564

Don Gagne's avatar
Don Gagne committed
1565 1566
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1567
    visualItems->insert(0, settingsItem);
1568

1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593
    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;
                    }
1594 1595
                }
            }
1596

1597 1598 1599
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1600
        }
Don Gagne's avatar
Don Gagne committed
1601 1602
    } else if (_managerVehicle->homePosition().isValid()) {
        settingsItem->setCoordinate(_managerVehicle->homePosition());
1603 1604
    }
}
1605

1606
int MissionController::resumeMissionIndex(void) const
1607
{
1608

1609
    int resumeIndex = 0;
1610

1611
    if (!_editMode) {
1612
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1613
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1614 1615
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1616 1617
        } else {
            resumeIndex = 0;
1618 1619 1620 1621 1622
        }
    }

    return resumeIndex;
}
1623

1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634 1635 1636
int MissionController::currentMissionIndex(void) const
{
    if (_editMode) {
        return -1;
    } else {
        int currentIndex = _missionManager->currentIndex();
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
            currentIndex++;
        }
        return currentIndex;
    }
}

1637
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1638 1639
{
    if (!_editMode) {
1640
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1641 1642 1643
            sequenceNumber++;
        }

1644 1645
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1646 1647
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
1648
        emit currentMissionIndexChanged(currentMissionIndex());
1649 1650
    }
}
1651

1652
bool MissionController::syncInProgress(void) const
1653
{
1654
    return _missionManager->inProgress();
1655 1656 1657 1658 1659 1660 1661 1662 1663 1664 1665 1666
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1667
    }
1668
}
1669

1670 1671
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1672 1673 1674
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, vehicle);

1675 1676 1677 1678 1679 1680
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1681
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
1682 1683 1684
        if (settingsItem) {
            scanIndex++;
            settingsItem->scanForMissionSettings(visualItems, scanIndex);
1685 1686 1687 1688
            continue;
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1689
        if (simpleItem) {
1690 1691 1692 1693 1694
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1695 1696 1697
        }
    }
}
1698 1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709 1710

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
1711 1712 1713 1714 1715 1716 1717 1718
    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();
    }
1719
}
1720 1721 1722 1723 1724 1725

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

    complexItems.append(_surveyMissionItemName);
1726
    if (_controllerVehicle->fixedWing()) {
1727 1728 1729 1730 1731
        complexItems.append(_fwLandingMissionItemName);
    }

    return complexItems;
}
1732

1733 1734
void MissionController::resumeMission(int resumeIndex)
{
1735
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1736 1737
        resumeIndex--;
    }
1738
    _missionManager->generateResumeMission(resumeIndex);
1739
}
1740 1741 1742 1743 1744 1745 1746 1747 1748

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1749 1750 1751 1752 1753 1754 1755 1756 1757 1758

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

1760 1761 1762 1763 1764 1765 1766
void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
1767 1768 1769 1770 1771 1772

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
1773 1774 1775

bool MissionController::showPlanFromManagerVehicle (void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1776
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle" << _editMode;
DonLakeFlyer's avatar
DonLakeFlyer committed
1777 1778
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
1779
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
1780 1781 1782 1783 1784 1785 1786 1787 1788 1789 1790 1791 1792 1793 1794 1795 1796 1797 1798
    } 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;
        }
    }
}

1799
void MissionController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1800
{
1801 1802
    // Fly view always reloads on send complete
    if (!error && !_editMode) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1803 1804 1805 1806
        showPlanFromManagerVehicle();
    }
}

1807
void MissionController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
1808
{
1809 1810 1811 1812
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1813
}