MissionController.cc 69.5 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 = newControllerMissionItems;

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

179
        if (_editMode) {
180
            MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
181
        }
182

183
        _initAllVisualItems();
184
        emit newItemsFromVehicle();
185
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
186
    _itemsRequested = false;
187 188
}

189
void MissionController::loadFromVehicle(void)
190
{
DonLakeFlyer's avatar
DonLakeFlyer committed
191 192 193 194 195 196 197 198
    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();
    }
199 200
}

201
void MissionController::sendToVehicle(void)
202
{
DonLakeFlyer's avatar
DonLakeFlyer committed
203 204 205 206 207
    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
208
        qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
DonLakeFlyer's avatar
DonLakeFlyer committed
209 210 211 212 213 214 215 216 217
        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
218 219
}

220 221 222 223 224
/// 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
225 226 227 228
    if (visualMissionItems->count() == 0) {
        return false;
    }

229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244
    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
245
    MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
246 247 248 249 250 251 252
    if (settingsItem) {
        endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
    }

    return endActionSet;
}

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

258
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
259

260
        vehicle->missionManager()->writeMissionItems(rgMissionItems);
261

262 263
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
264
        }
265 266
    }
}
267

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

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

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

    _recalcAll();

304
    return newItem->sequenceNumber();
305 306
}

307
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
308
{
309 310
    ComplexMissionItem* newItem;

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

343
    _visualItems->insert(i, newItem);
344 345 346

    _recalcAll();

347
    return newItem->sequenceNumber();
348 349
}

350 351
void MissionController::removeMissionItem(int index)
{
352 353 354 355 356 357
    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);
358
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
359

360
    _deinitVisualItem(item);
361
    item->deleteLater();
362

363 364 365 366 367 368 369 370 371 372
    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;
            }
        }

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

391
    _recalcAll();
392
    setDirty(true);
393 394
}

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

409
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
410 411 412 413 414 415 416 417 418
{
    // 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)) {
419 420 421
        return false;
    }

422
    // Read complex items
423
    QList<SurveyMissionItem*> surveyItems;
424 425 426 427
    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];
428

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

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

443 444 445 446 447
    // 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
448
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
449

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

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

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

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

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

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

    return true;
}

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

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

523
    // Mission Settings
524
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
525

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

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

654 655 656 657 658 659 660 661
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;
662 663 664 665 666 667
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
668 669

    if (fileVersion == 1) {
670
        return _loadJsonMissionFileV1(json, visualItems, errorString);
671
    } else {
672
        return _loadJsonMissionFileV2(json, visualItems, errorString);
673 674 675
    }
}

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

    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;
689
            plannedHomePositionInFile = true;
690 691 692
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
693
            plannedHomePositionInFile = false;
694 695 696 697
        }
    }

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

702
        while (!stream.atEnd()) {
703
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
704 705

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

722
    if (!plannedHomePositionInFile) {
723 724 725 726 727
        // 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
728 729
            }
        }
730 731 732
    }

    return true;
733 734
}

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

743
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
744 745

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

749
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
750

Don Gagne's avatar
Don Gagne committed
751
    _initAllVisualItems();
752
}
753

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

760
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785
        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;
786
    }
787

788 789 790 791 792 793 794 795 796 797 798 799 800
    _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);
801
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
802 803 804 805 806 807
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
808
    return true;
809 810
}

811
void MissionController::save(QJsonObject& json)
812
{
813
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
814

815
    // Mission settings
816

817 818 819 820 821 822 823 824
    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;
825 826 827 828
    json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
829

830
    // Save the visual items
831

832 833 834
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
835

836 837
        visualItem->save(rgJsonMissionItems);
    }
838

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

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

854
    json[_jsonItemsKey] = rgJsonMissionItems;
855 856
}

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

    // Convert to fixed altitudes

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

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

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

    distanceOk = true;

892
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
893 894
}

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

900
    bool showHomePosition = _settingsItem->coordinate().isValid();
901

902
    qCDebug(MissionControllerLog) << "_recalcWaypointLines showHomePosition" << showHomePosition;
903

Nate Weibley's avatar
Nate Weibley committed
904 905
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
906 907 908 909 910 911 912
    _waypointLines.clear();

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


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

        if (item->specifiesCoordinate()) {
            if (!item->isStandaloneCoordinate()) {
                firstCoordinateItem = false;
                VisualItemPair pair(lastCoordinateItem, item);
925
                if (lastCoordinateItem != _settingsItem || (showHomePosition && linkBackToHome)) {
926 927
                    if (old_table.contains(pair)) {
                        // Do nothing, this segment already exists and is wired up
Nate Weibley's avatar
Nate Weibley committed
928
                        _linesTable[pair] = old_table.take(pair);
929 930 931 932
                    } 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
933
                                endNotifier    = &VisualMissionItem::coordinateChanged;
934 935 936 937 938 939
                        // 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
940
                        connect(item, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcMissionFlightStatus);
Nate Weibley's avatar
Nate Weibley committed
941
                        _linesTable[pair] = linevect;
942 943 944 945 946 947 948 949 950 951
                    }
                }
                lastCoordinateItem = item;
            }
        }
    }

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
952 953
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
954 955 956 957 958 959 960 961 962 963
            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
964
    _recalcMissionFlightStatus();
965 966 967 968

    emit waypointLinesChanged();
}

969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 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);
        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
999
void MissionController::_recalcMissionFlightStatus()
1000
{
1001
    if (!_visualItems->count()) {
1002
        return;
1003
    }
1004 1005 1006 1007

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

1008
    bool showHomePosition = _settingsItem->coordinate().isValid();
1009

DonLakeFlyer's avatar
DonLakeFlyer committed
1010
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1011

1012 1013 1014
    // 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.
1015

1016
    // No values for first item
1017
    lastCoordinateItem->setAltDifference(0.0);
1018
    lastCoordinateItem->setAzimuth(0.0);
1019
    lastCoordinateItem->setDistance(0.0);
1020

1021 1022
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1023 1024
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1025

1026
    _resetMissionFlightStatus();
1027

DonLakeFlyer's avatar
DonLakeFlyer committed
1028
    bool vtolInHover = true;
Don Gagne's avatar
Don Gagne committed
1029
    bool linkBackToHome = false;
1030

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

1036 1037
        // Assume the worst
        item->setAzimuth(0.0);
1038
        item->setDistance(0.0);
1039

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

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

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

1071 1072 1073 1074 1075 1076 1077 1078
        // 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
1079
        if (simpleItem && _controllerVehicle->vtol()) {
1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093
            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;
1094 1095
                }
            }
1096 1097 1098
                break;
            default:
                break;
1099
            }
Don Gagne's avatar
Don Gagne committed
1100 1101
        }

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

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

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

1118 1119 1120 1121 1122 1123 1124 1125 1126 1127
            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
1128
                firstCoordinateItem = false;
1129
                if (lastCoordinateItem != _settingsItem || linkBackToHome) {
1130 1131
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1132

1133
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1134 1135 1136
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1137

1138
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1139

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

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

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

                item->setMissionFlightStatus(_missionFlightStatus);
1181
            }
1182 1183

            lastCoordinateItem = item;
1184 1185
        }
    }
1186
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1187

1188 1189 1190
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1191

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

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

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

1221 1222 1223
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1224 1225 1226 1227 1228 1229
    // 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));

1230 1231
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1232 1233 1234
    }
}

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

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

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

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

1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271
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));
        }
    }
}


1272 1273
void MissionController::_recalcAll(void)
{
1274 1275 1276
    if (_editMode) {
        _setPlannedHomePositionFromFirstCoordinate();
    }
1277
    _recalcSequence();
1278 1279 1280 1281
    _recalcChildItems();
    _recalcWaypointLines();
}

1282
/// Initializes a new set of mission items
1283
void MissionController::_initAllVisualItems(void)
1284
{
1285 1286
    // Setup home position at index 0

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

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

1300
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
1301
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);
1302

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

1308
    _recalcAll();
1309

1310
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1311 1312 1313
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1314
    emit containsItemsChanged(containsItems());
1315
    emit plannedHomePositionChanged(plannedHomePosition());
1316

1317
    setDirty(false);
1318 1319
}

1320
void MissionController::_deinitAllVisualItems(void)
1321
{
1322 1323 1324
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1325 1326
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1327 1328
    }

1329
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1330
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1331 1332
}

1333
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1334
{
1335
    setDirty(false);
1336

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

1344 1345 1346 1347 1348 1349 1350 1351
    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";
        }
1352 1353
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1354
        if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1355
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcMissionFlightStatus);
1356 1357 1358
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1359
    }
1360 1361
}

1362
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1363
{
1364 1365
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1366 1367
}

1368
void MissionController::_itemCommandChanged(void)
1369
{
1370 1371
    _recalcChildItems();
    _recalcWaypointLines();
1372 1373
}

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

1383 1384
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
1385
        qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1386 1387
        return;
    }
1388

1389 1390
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1391 1392
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1393 1394 1395 1396 1397 1398 1399 1400 1401
    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);
1402

1403 1404
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1405
    }
1406

1407
    emit complexMissionItemNamesChanged();
1408
    emit resumeMissionIndexChanged();
1409 1410
}

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

void MissionController::_inProgressChanged(bool inProgress)
1428
{
1429
    emit syncInProgressChanged(inProgress);
1430
}
1431

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

1438 1439 1440 1441 1442 1443
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

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

1459
    if (found) {
1460 1461
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1462 1463 1464
    }

    return found;
1465
}
1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478

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

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

Don Gagne's avatar
Don Gagne committed
1484 1485
    qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;

1486
    visualItems->insert(0, settingsItem);
1487

1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512
    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;
                    }
1513 1514
                }
            }
1515

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

1525
int MissionController::resumeMissionIndex(void) const
1526
{
1527

1528
    int resumeIndex = 0;
1529

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

    return resumeIndex;
}
1542

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

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

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

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

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1586
    }
1587
}
1588

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

1594 1595 1596 1597 1598 1599
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

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

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

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
1630 1631 1632 1633 1634 1635 1636 1637
    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();
    }
1638
}
1639 1640 1641 1642 1643 1644

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

    complexItems.append(_surveyMissionItemName);
1645
    if (_controllerVehicle->fixedWing()) {
1646 1647 1648 1649 1650
        complexItems.append(_fwLandingMissionItemName);
    }

    return complexItems;
}
1651

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

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

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

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

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
1692 1693 1694

bool MissionController::showPlanFromManagerVehicle (void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1695
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle" << _editMode;
DonLakeFlyer's avatar
DonLakeFlyer committed
1696 1697
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
1698
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716 1717
    } 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;
        }
    }
}

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

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