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


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

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

34 35
QGC_LOGGING_CATEGORY(MissionControllerLog, "MissionControllerLog")

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

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

const int   MissionController::_missionFileVersion =            2;
51

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

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

71 72
}

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

    // Battery information

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

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

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

115 116
}

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

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

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

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

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

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

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

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

        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
171
        _visualItems->deleteLater();
172
        _settingsItem = NULL;
173 174
        _visualItems = 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 208 209 210 211 212 213 214 215 216
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::sendToVehicle called while offline";
    } else if (syncInProgress()) {
        qCWarning(MissionControllerLog) << "MissionControllerLog::sendToVehicle called while syncInProgress";
    } else {
        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
217 218
}

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

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

    return endActionSet;
}

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

257
        _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
258

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

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

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

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

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

    _recalcAll();

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

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

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

336
    _visualItems->insert(i, newItem);
337 338 339

    _recalcAll();

340
    return newItem->sequenceNumber();
341 342
}

343 344
void MissionController::removeMissionItem(int index)
{
345 346 347 348 349 350
    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);
351
    VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(index));
352

353
    _deinitVisualItem(item);
354
    item->deleteLater();
355

356 357 358 359 360 361 362 363 364 365 366 367 368 369 370
    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;
            }
        }

        // If there is no longer a survey item in the mission remove the gimbal pitch command
        if (!foundSurvey) {
            bool rollSupported = false;
            bool pitchSupported = false;
            bool yawSupported = false;
371
            if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
372 373 374 375 376 377 378 379 380
                MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
                CameraSection* cameraSection = settingsItem->cameraSection();
                if (cameraSection->specifyGimbal() && cameraSection->gimbalYaw()->rawValue().toDouble() == -90.0 && cameraSection->gimbalPitch()->rawValue().toDouble() == 0.0) {
                    cameraSection->setSpecifyGimbal(false);
                }
            }
        }
    }

381
    _recalcAll();
382
    setDirty(true);
383 384
}

385
void MissionController::removeAll(void)
386
{
387 388
    if (_visualItems) {
        _deinitAllVisualItems();
Don Gagne's avatar
Don Gagne committed
389
        _visualItems->deleteLater();
390
        _settingsItem = NULL;
391
        _visualItems = new QmlObjectListModel(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
392
        _addMissionSettings(_visualItems, false /* addToCenter */);
393
        _initAllVisualItems();
394
        setDirty(true);
395
        _resetMissionFlightStatus();
Don Gagne's avatar
Don Gagne committed
396 397 398
    }
}

399
bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
400 401 402 403 404 405 406 407 408
{
    // 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)) {
409 410 411
        return false;
    }

412
    // Read complex items
413
    QList<SurveyMissionItem*> surveyItems;
414 415 416 417
    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];
418

419 420 421 422 423
        if (!itemValue.isObject()) {
            errorString = QStringLiteral("Mission item is not an object");
            return false;
        }

424
        SurveyMissionItem* item = new SurveyMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
425 426
        const QJsonObject itemObject = itemValue.toObject();
        if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
427
            surveyItems.append(item);
428 429
        } else {
            return false;
430
        }
431
    }
432

433 434 435 436 437
    // 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
438
    QJsonArray itemArray(json[_jsonItemsKey].toArray());
439

440
    qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
441 442 443 444
    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
445 446
        if (nextComplexItemIndex < surveyItems.count()) {
            SurveyMissionItem* complexItem = surveyItems[nextComplexItemIndex];
447 448 449 450 451 452 453 454 455 456 457 458 459 460

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

461 462 463 464 465
            if (!itemValue.isObject()) {
                errorString = QStringLiteral("Mission item is not an object");
                return false;
            }

Don Gagne's avatar
Don Gagne committed
466
            const QJsonObject itemObject = itemValue.toObject();
467
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
Don Gagne's avatar
Don Gagne committed
468
            if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
469
                qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
470
                nextSequenceNumber = item->lastSequenceNumber() + 1;
471
                visualItems->append(item);
472 473 474 475
            } else {
                return false;
            }
        }
476
    } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
477 478

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

Don Gagne's avatar
Don Gagne committed
481
        if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
482
            MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
483 484 485
            settingsItem->setCoordinate(item->coordinate());
            visualItems->insert(0, settingsItem);
            item->deleteLater();
486 487 488 489
        } else {
            return false;
        }
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
490
        _addMissionSettings(visualItems, true /* addToCenter */);
491 492 493 494 495
    }

    return true;
}

496
bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
Don Gagne's avatar
Don Gagne committed
497 498 499 500 501 502
{
    // Validate root object keys
    QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
        { _jsonPlannedHomePositionKey,      QJsonValue::Array,  true },
        { _jsonItemsKey,                    QJsonValue::Array,  true },
        { _jsonFirmwareTypeKey,             QJsonValue::Double, true },
503
        { _jsonVehicleTypeKey,              QJsonValue::Double, true },
504 505
        { _jsonCruiseSpeedKey,              QJsonValue::Double, false },
        { _jsonHoverSpeedKey,               QJsonValue::Double, false },
Don Gagne's avatar
Don Gagne committed
506 507 508 509 510 511 512
    };
    if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
        return false;
    }

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

513
    // Mission Settings
514
    AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
515

516 517 518 519 520
    if (_masterController->offline()) {
        // We only update if offline since if we are online we use the online vehicle settings
        appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType((MAV_AUTOPILOT)json[_jsonVehicleTypeKey].toInt()));
        appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType((MAV_TYPE)json[_jsonVehicleTypeKey].toInt()));
    }
521
    if (json.contains(_jsonCruiseSpeedKey)) {
522
        appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
523 524
    }
    if (json.contains(_jsonHoverSpeedKey)) {
525
        appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
526 527
    }

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

642 643 644 645 646 647 648 649
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;
650 651 652 653 654 655
    JsonHelper::validateQGCJsonFile(json,
                                    _jsonFileTypeValue,    // expected file type
                                    1,                     // minimum supported version
                                    2,                     // maximum supported version
                                    fileVersion,
                                    errorString);
656 657

    if (fileVersion == 1) {
658
        return _loadJsonMissionFileV1(json, visualItems, errorString);
659
    } else {
660
        return _loadJsonMissionFileV2(json, visualItems, errorString);
661 662 663
    }
}

664
bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
665
{
666 667
    bool firstItem = true;
    bool plannedHomePositionInFile = false;
668 669 670 671 672 673 674 675 676

    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;
677
            plannedHomePositionInFile = true;
678 679 680
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
681
            plannedHomePositionInFile = false;
682 683 684 685
        }
    }

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

690
        while (!stream.atEnd()) {
691
            SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, visualItems);
692 693

            if (item->load(stream)) {
694 695 696 697 698 699
                if (firstItem && plannedHomePositionInFile) {
                    settingsItem->setCoordinate(item->coordinate());
                } else {
                    visualItems->append(item);
                }
                firstItem = false;
700 701 702 703 704 705
            } else {
                errorString = QStringLiteral("The mission file is corrupted.");
                return false;
            }
        }
    } else {
706
        errorString = QStringLiteral("The mission file is not compatible with this version of %1.").arg(qgcApp()->applicationName());
707 708 709
        return false;
    }

710
    if (!plannedHomePositionInFile) {
711 712 713 714 715
        // 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
716 717
            }
        }
718 719 720
    }

    return true;
721 722
}

723
void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
724
{
Don Gagne's avatar
Don Gagne committed
725 726 727
    if (_visualItems) {
        _deinitAllVisualItems();
        _visualItems->deleteLater();
728
        _settingsItem = NULL;
Don Gagne's avatar
Don Gagne committed
729 730
    }

731
    _visualItems = loadedVisualItems;
Don Gagne's avatar
Don Gagne committed
732 733

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

737
    MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
738

Don Gagne's avatar
Don Gagne committed
739
    _initAllVisualItems();
740
}
741

742 743 744 745 746 747
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
    QString errorStr;
    QString errorMessage = tr("Mission: %1");
    QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);

748
    if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773
        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;
774
    }
775

776 777 778 779 780 781 782 783 784 785 786 787 788
    _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);
789
    if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
790 791 792 793 794 795
        errorString = errorMessage.arg(errorStr);
        return false;
    }

    _initLoadedVisualItems(loadedVisualItems);

Don Gagne's avatar
Don Gagne committed
796
    return true;
797 798
}

799
void MissionController::save(QJsonObject& json)
800
{
801
    json[JsonHelper::jsonVersionKey] = _missionFileVersion;
802

803
    // Mission settings
804

805 806 807 808 809 810 811 812
    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;
813 814 815 816
    json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
    json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
    json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
    json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
817

818
    // Save the visual items
819

820 821 822
    QJsonArray rgJsonMissionItems;
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
823

824 825
        visualItem->save(rgJsonMissionItems);
    }
826

827 828 829
    // Mission settings has a special case for end mission action
    if (settingsItem) {
        QList<MissionItem*> rgMissionItems;
830

831 832 833 834 835
        if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
            QJsonObject saveObject;
            MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
            missionItem->save(saveObject);
            rgJsonMissionItems.append(saveObject);
836
        }
837 838
        for (int i=0; i<rgMissionItems.count(); i++) {
            rgMissionItems[i]->deleteLater();
839 840 841
        }
    }

842
    json[_jsonItemsKey] = rgJsonMissionItems;
843 844
}

845
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
846
{
Don Gagne's avatar
Don Gagne committed
847
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
848
    QGeoCoordinate  prevCoord =     prevItem->exitCoordinate();
849 850 851 852
    bool            distanceOk =    false;

    // Convert to fixed altitudes

853
    distanceOk = true;
854
    if (currentItem->coordinateHasRelativeAltitude()) {
855 856
        currentCoord.setAltitude(homeAlt + currentCoord.altitude());
    }
857
    if (prevItem->exitCoordinateHasRelativeAltitude()) {
858
        prevCoord.setAltitude(homeAlt + prevCoord.altitude());
859 860 861
    }

    if (distanceOk) {
Don Gagne's avatar
Don Gagne committed
862 863 864
        *altDifference = currentCoord.altitude() - prevCoord.altitude();
        *distance = prevCoord.distanceTo(currentCoord);
        *azimuth = prevCoord.azimuthTo(currentCoord);
865
    } else {
Don Gagne's avatar
Don Gagne committed
866
        *altDifference = 0.0;
867
        *azimuth = 0.0;
868
        *distance = 0.0;
869 870 871
    }
}

872
double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
873 874 875 876 877 878 879
{
    QGeoCoordinate  currentCoord =  currentItem->coordinate();
    QGeoCoordinate  homeCoord =     homeItem->exitCoordinate();
    bool            distanceOk =    false;

    distanceOk = true;

880
    return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
881 882
}

883 884
void MissionController::_recalcWaypointLines(void)
{
885 886 887
    bool                firstCoordinateItem =   true;
    VisualMissionItem*  lastCoordinateItem =    qobject_cast<VisualMissionItem*>(_visualItems->get(0));

888
    bool showHomePosition = _settingsItem->coordinate().isValid();
889

890
    qCDebug(MissionControllerLog) << "_recalcWaypointLines showHomePosition" << showHomePosition;
891

Nate Weibley's avatar
Nate Weibley committed
892 893
    CoordVectHashTable old_table = _linesTable;
    _linesTable.clear();
894 895 896 897 898 899 900
    _waypointLines.clear();

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


901
        // If we still haven't found the first coordinate item and we hit a takeoff command, link back to home
902 903
        if (firstCoordinateItem &&
                item->isSimpleItem() &&
904 905
                (qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF ||
                 qobject_cast<SimpleMissionItem*>(item)->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
906 907 908 909 910 911 912
            linkBackToHome = true;
        }

        if (item->specifiesCoordinate()) {
            if (!item->isStandaloneCoordinate()) {
                firstCoordinateItem = false;
                VisualItemPair pair(lastCoordinateItem, item);
913
                if (lastCoordinateItem != _settingsItem || (showHomePosition && linkBackToHome)) {
914 915
                    if (old_table.contains(pair)) {
                        // Do nothing, this segment already exists and is wired up
Nate Weibley's avatar
Nate Weibley committed
916
                        _linesTable[pair] = old_table.take(pair);
917 918 919 920
                    } 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
921
                                endNotifier    = &VisualMissionItem::coordinateChanged;
922 923 924 925 926 927
                        // 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
928
                        connect(item, &VisualMissionItem::coordinateChanged, this, &MissionController::_recalcMissionFlightStatus);
Nate Weibley's avatar
Nate Weibley committed
929
                        _linesTable[pair] = linevect;
930 931 932 933 934 935 936 937 938 939
                    }
                }
                lastCoordinateItem = item;
            }
        }
    }

    {
        // Create a temporary QObjectList and replace the model data
        QObjectList objs;
Nate Weibley's avatar
Nate Weibley committed
940 941
        objs.reserve(_linesTable.count());
        foreach(CoordinateVector *vect, _linesTable.values()) {
942 943 944 945 946 947 948 949 950 951
            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
952
    _recalcMissionFlightStatus();
953 954 955 956

    emit waypointLinesChanged();
}

957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986
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
987
void MissionController::_recalcMissionFlightStatus()
988
{
989
    if (!_visualItems->count()) {
990
        return;
991
    }
992 993 994 995

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

996
    bool showHomePosition = _settingsItem->coordinate().isValid();
997

DonLakeFlyer's avatar
DonLakeFlyer committed
998
    qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
999

1000 1001 1002
    // 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.
1003

1004
    // No values for first item
1005
    lastCoordinateItem->setAltDifference(0.0);
1006
    lastCoordinateItem->setAzimuth(0.0);
1007
    lastCoordinateItem->setDistance(0.0);
1008

1009 1010
    double minAltSeen = 0.0;
    double maxAltSeen = 0.0;
1011 1012
    const double homePositionAltitude = _settingsItem->coordinate().altitude();
    minAltSeen = maxAltSeen = _settingsItem->coordinate().altitude();
1013

1014
    _resetMissionFlightStatus();
1015

DonLakeFlyer's avatar
DonLakeFlyer committed
1016
    bool vtolInHover = true;
Don Gagne's avatar
Don Gagne committed
1017
    bool linkBackToHome = false;
1018

DonLakeFlyer's avatar
DonLakeFlyer committed
1019
    for (int i=0; i<_visualItems->count(); i++) {
1020
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1021 1022 1023
        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);

1024 1025
        // Assume the worst
        item->setAzimuth(0.0);
1026
        item->setDistance(0.0);
1027

DonLakeFlyer's avatar
DonLakeFlyer committed
1028 1029 1030
        // Look for speed changed
        double newSpeed = item->specifiedFlightSpeed();
        if (!qIsNaN(newSpeed)) {
1031
            if (_controllerVehicle->multiRotor()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1032
                _missionFlightStatus.hoverSpeed = newSpeed;
1033
            } else if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1034 1035
                if (vtolInHover) {
                    _missionFlightStatus.hoverSpeed = newSpeed;
1036
                } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1037
                    _missionFlightStatus.cruiseSpeed = newSpeed;
1038
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1039 1040
            } else {
                _missionFlightStatus.cruiseSpeed = newSpeed;
1041
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1042 1043 1044 1045
            _missionFlightStatus.vehicleSpeed = newSpeed;
        }

        // Look for gimbal change
1046
        if (_controllerVehicle->vehicleYawsToNextWaypointInMission()) {
1047 1048 1049 1050 1051
            // We current only support gimbal display in this mode
            double gimbalYaw = item->specifiedGimbalYaw();
            if (!qIsNaN(gimbalYaw)) {
                _missionFlightStatus.gimbalYaw = gimbalYaw;
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1052 1053 1054 1055 1056
        }

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

1059 1060 1061 1062 1063 1064 1065 1066
        // 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
1067
        if (simpleItem && _controllerVehicle->vtol()) {
1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081
            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;
1082 1083
                }
            }
1084 1085 1086
                break;
            default:
                break;
1087
            }
Don Gagne's avatar
Don Gagne committed
1088 1089
        }

1090
        if (item->specifiesCoordinate()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1091 1092
            // Update vehicle yaw assuming direction to next waypoint
            if (item != lastCoordinateItem) {
1093 1094
                _missionFlightStatus.vehicleYaw = lastCoordinateItem->exitCoordinate().azimuthTo(item->coordinate());
                lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
DonLakeFlyer's avatar
DonLakeFlyer committed
1095 1096
            }

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

1099
            double absoluteAltitude = item->coordinate().altitude();
1100
            if (item->coordinateHasRelativeAltitude()) {
1101 1102 1103 1104 1105
                absoluteAltitude += homePositionAltitude;
            }
            minAltSeen = std::min(minAltSeen, absoluteAltitude);
            maxAltSeen = std::max(maxAltSeen, absoluteAltitude);

1106 1107 1108 1109 1110 1111 1112 1113 1114 1115
            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
1116
                firstCoordinateItem = false;
1117
                if (lastCoordinateItem != _settingsItem || linkBackToHome) {
1118 1119
                    // This is a subsequent waypoint or we are forcing the first waypoint back to home
                    double azimuth, distance, altDifference;
1120

1121
                    _calcPrevWaypointValues(homePositionAltitude, item, lastCoordinateItem, &azimuth, &distance, &altDifference);
1122 1123 1124
                    item->setAltDifference(altDifference);
                    item->setAzimuth(azimuth);
                    item->setDistance(distance);
1125

1126
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1127

DonLakeFlyer's avatar
DonLakeFlyer committed
1128 1129 1130
                    // Calculate time/distance
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1131
                    if (_controllerVehicle->vtol()) {
1132
                        if (vtolInHover) {
1133
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
1134
                        } else {
1135
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
1136 1137
                        }
                    } else {
1138
                        if (_controllerVehicle->multiRotor()) {
1139
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1140
                        } else {
1141
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1142
                        }
1143
                    }
1144
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1145

1146
                if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1147 1148
                    // Add in distance/time inside complex items as well
                    double distance = complexItem->complexDistance();
1149
                    _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
DonLakeFlyer's avatar
DonLakeFlyer committed
1150

1151 1152
                    double hoverTime = distance / _missionFlightStatus.hoverSpeed;
                    double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1153
                    if (_controllerVehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1154
                        if (vtolInHover) {
1155
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1156
                        } else {
1157
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1158 1159
                        }
                    } else {
1160
                        if (_controllerVehicle->multiRotor()) {
1161
                            _addHoverTime(hoverTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1162
                        } else {
1163
                            _addCruiseTime(cruiseTime, distance, item->sequenceNumber());
DonLakeFlyer's avatar
DonLakeFlyer committed
1164 1165
                        }
                    }
1166
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
1167 1168

                item->setMissionFlightStatus(_missionFlightStatus);
1169
            }
1170 1171

            lastCoordinateItem = item;
1172 1173
        }
    }
1174
    lastCoordinateItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1175

1176 1177 1178
    if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
        _missionFlightStatus.batteryChangePoint = 0;
    }
1179

DonLakeFlyer's avatar
DonLakeFlyer committed
1180 1181 1182 1183 1184 1185 1186
    emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
    emit missionDistanceChanged(_missionFlightStatus.totalDistance);
    emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
    emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
    emit missionTimeChanged();
    emit missionHoverTimeChanged();
    emit missionCruiseTimeChanged();
1187 1188
    emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
    emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
1189

1190 1191
    // Walk the list again calculating altitude percentages
    double altRange = maxAltSeen - minAltSeen;
1192 1193
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1194 1195 1196

        if (item->specifiesCoordinate()) {
            double absoluteAltitude = item->coordinate().altitude();
1197
            if (item->coordinateHasRelativeAltitude()) {
1198 1199 1200 1201 1202 1203
                absoluteAltitude += homePositionAltitude;
            }
            if (altRange == 0.0) {
                item->setAltPercent(0.0);
            } else {
                item->setAltPercent((absoluteAltitude - minAltSeen) / altRange);
1204
            }
1205 1206 1207 1208
        }
    }
}

1209 1210 1211
// This will update the sequence numbers to be sequential starting from 0
void MissionController::_recalcSequence(void)
{
1212 1213 1214 1215 1216 1217
    // 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));

1218 1219
        item->setSequenceNumber(sequenceNumber);
        sequenceNumber = item->lastSequenceNumber() + 1;
1220 1221 1222
    }
}

1223 1224 1225
// This will update the child item hierarchy
void MissionController::_recalcChildItems(void)
{
1226
    VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1227 1228 1229

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

1230 1231
    for (int i=1; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1232 1233 1234 1235 1236

        // Set up non-coordinate item child hierarchy
        if (item->specifiesCoordinate()) {
            item->childItems()->clear();
            currentParentItem = item;
1237
        } else if (item->isSimpleItem()) {
1238 1239 1240 1241 1242
            currentParentItem->childItems()->append(item);
        }
    }
}

1243 1244 1245 1246 1247 1248 1249 1250 1251 1252 1253 1254 1255 1256 1257 1258 1259
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));
        }
    }
}


1260 1261
void MissionController::_recalcAll(void)
{
1262 1263 1264
    if (_editMode) {
        _setPlannedHomePositionFromFirstCoordinate();
    }
1265
    _recalcSequence();
1266 1267 1268 1269
    _recalcChildItems();
    _recalcWaypointLines();
}

1270
/// Initializes a new set of mission items
1271
void MissionController::_initAllVisualItems(void)
1272
{
1273 1274
    // Setup home position at index 0

1275 1276 1277
    _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
    if (!_settingsItem) {
        qWarning() << "First item not MissionSettingsItem";
1278 1279
        return;
    }
1280 1281 1282
    if (_editMode) {
        _settingsItem->setIsCurrentItem(true);
    }
1283

1284 1285
    if (!_editMode && _controllerVehicle) {
        _settingsItem->setCoordinate(_controllerVehicle->homePosition());
1286
    }
1287

1288
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
1289
    connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);
1290

1291 1292 1293 1294
    for (int i=0; i<_visualItems->count(); i++) {
        VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
        _initVisualItem(item);
    }
1295

1296
    _recalcAll();
1297

1298
    connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1299 1300 1301
    connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);

    emit visualItemsChanged();
1302
    emit containsItemsChanged(containsItems());
1303
    emit plannedHomePositionChanged(plannedHomePosition());
1304

1305
    setDirty(false);
1306 1307
}

1308
void MissionController::_deinitAllVisualItems(void)
1309
{
1310 1311 1312
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
    disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::plannedHomePositionChanged);

1313 1314
    for (int i=0; i<_visualItems->count(); i++) {
        _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1315 1316
    }

1317
    disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::dirtyChanged);
1318
    disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
1319 1320
}

1321
void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1322
{
1323
    setDirty(false);
1324

1325
    connect(visualItem, &VisualMissionItem::specifiesCoordinateChanged,                 this, &MissionController::_recalcWaypointLines);
1326 1327
    connect(visualItem, &VisualMissionItem::coordinateHasRelativeAltitudeChanged,       this, &MissionController::_recalcWaypointLines);
    connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged,   this, &MissionController::_recalcWaypointLines);
DonLakeFlyer's avatar
DonLakeFlyer committed
1328 1329
    connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged,                this, &MissionController::_recalcMissionFlightStatus);
    connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged,                  this, &MissionController::_recalcMissionFlightStatus);
1330
    connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged,                  this, &MissionController::_recalcSequence);
1331

1332 1333 1334 1335 1336 1337 1338 1339
    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";
        }
1340 1341
    } else {
        ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1342
        if (complexItem) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1343
            connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcMissionFlightStatus);
1344 1345 1346
        } else {
            qWarning() << "ComplexMissionItem not found";
        }
1347
    }
1348 1349
}

1350
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1351
{
1352 1353
    // Disconnect all signals
    disconnect(visualItem, 0, 0, 0);
1354 1355
}

1356
void MissionController::_itemCommandChanged(void)
1357
{
1358 1359
    _recalcChildItems();
    _recalcWaypointLines();
1360 1361
}

1362
void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
1363
{
1364 1365 1366 1367 1368 1369
    if (_managerVehicle) {
        _missionManager->disconnect(this);
        _managerVehicle->disconnect(this);
        _managerVehicle = NULL;
        _missionManager = NULL;
    }
1370

1371 1372 1373 1374 1375
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
        qWarning() << "RallyPointController::managerVehicleChanged managerVehicle=NULL";
        return;
    }
1376

1377 1378
    _missionManager = _managerVehicle->missionManager();
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
1379 1380
    connect(_missionManager, &MissionManager::sendComplete,             this, &MissionController::_managerSendComplete);
    connect(_missionManager, &MissionManager::removeAllComplete,        this, &MissionController::_managerRemoveAllComplete);
1381 1382 1383 1384 1385 1386 1387 1388 1389 1390
    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(_missionManager, &MissionManager::cameraFeedback,           this, &MissionController::_cameraFeedback);
    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);
1391

1392 1393
    if (!_masterController->offline()) {
        _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
1394
    }
1395

1396
    emit complexMissionItemNamesChanged();
1397
    emit resumeMissionIndexChanged();
1398 1399
}

1400
void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
1401
{
1402 1403
    if (_visualItems) {
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1404
        if (settingsItem) {
1405
            settingsItem->setCoordinate(homePosition);
1406
        } else {
1407
            qWarning() << "First item is not MissionSettingsItem";
1408
        }
1409 1410 1411 1412
        if (_visualItems->count() == 1) {
            // Don't let this trip the dirty bit
            _visualItems->setDirty(false);
        }
1413
    }
1414 1415 1416
}

void MissionController::_inProgressChanged(bool inProgress)
1417
{
1418
    emit syncInProgressChanged(inProgress);
1419
}
1420

1421
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
1422
{
1423 1424 1425
    bool        found = false;
    double      foundAltitude;
    MAV_FRAME   foundFrame;
1426

1427 1428 1429 1430 1431 1432
    if (newIndex > _visualItems->count()) {
        return false;
    }
    newIndex--;

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

1435 1436 1437
        if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
            if (visualItem->isSimpleItem()) {
                SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1438
                if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
1439 1440 1441
                    foundAltitude = simpleItem->exitCoordinate().altitude();
                    foundFrame = simpleItem->missionItem().frame();
                    found = true;
1442
                    break;
1443 1444
                }
            }
1445 1446 1447
        }
    }

1448
    if (found) {
1449 1450
        *prevAltitude = foundAltitude;
        *prevFrame = foundFrame;
1451 1452 1453
    }

    return found;
1454
}
1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467

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

1468
/// Add the Mission Settings complex item to the front of the items
DonLakeFlyer's avatar
DonLakeFlyer committed
1469
void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
1470
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1471
    MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
1472

1473
    visualItems->insert(0, settingsItem);
1474

1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499
    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;
                    }
1500 1501
                }
            }
1502

1503 1504 1505
            if (firstCoordSet) {
                settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
            }
1506
        }
1507
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1508
        settingsItem->setCoordinate(_controllerVehicle->homePosition());
1509 1510
    }
}
1511

1512
int MissionController::resumeMissionIndex(void) const
1513
{
1514

1515
    int resumeIndex = 0;
1516

1517
    if (!_editMode) {
1518
        resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1519
        if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1520 1521
            // Resume at the item previous to the item we were heading towards
            resumeIndex--;
1522 1523
        } else {
            resumeIndex = 0;
1524 1525 1526 1527 1528
        }
    }

    return resumeIndex;
}
1529

1530
void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1531 1532
{
    if (!_editMode) {
1533
        if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1534 1535 1536
            sequenceNumber++;
        }

1537 1538
        for (int i=0; i<_visualItems->count(); i++) {
            VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1539 1540 1541 1542
            item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
        }
    }
}
1543

1544
bool MissionController::syncInProgress(void) const
1545
{
1546
    return _missionManager->inProgress();
1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558
}

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


void MissionController::setDirty(bool dirty)
{
    if (_visualItems) {
        _visualItems->setDirty(dirty);
1559
    }
1560
}
1561

1562 1563
void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle)
{
1564 1565 1566
    // First we look for a Fixed Wing Landing Pattern which is at the end
    FixedWingLandingComplexItem::scanForItem(visualItems, vehicle);

1567 1568 1569 1570 1571 1572
    int scanIndex = 0;
    while (scanIndex < visualItems->count()) {
        VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);

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

1573
        MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
1574 1575 1576
        if (settingsItem) {
            scanIndex++;
            settingsItem->scanForMissionSettings(visualItems, scanIndex);
1577 1578 1579 1580
            continue;
        }

        SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1581
        if (simpleItem) {
1582 1583 1584 1585 1586
            scanIndex++;
            simpleItem->scanForSections(visualItems, scanIndex, vehicle);
        } else {
            // Complex item, can't have sections
            scanIndex++;
1587 1588 1589
        }
    }
}
1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602

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
1603 1604 1605 1606 1607 1608 1609 1610
    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();
    }
1611
}
1612 1613 1614 1615 1616 1617

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

    complexItems.append(_surveyMissionItemName);
1618
    if (_controllerVehicle->fixedWing()) {
1619 1620 1621 1622 1623
        complexItems.append(_fwLandingMissionItemName);
    }

    return complexItems;
}
1624

1625 1626
void MissionController::resumeMission(int resumeIndex)
{
1627
    if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1628 1629
        resumeIndex--;
    }
1630
    _missionManager->generateResumeMission(resumeIndex);
1631
}
1632 1633 1634 1635 1636 1637 1638 1639 1640

QGeoCoordinate MissionController::plannedHomePosition(void) const
{
    if (_settingsItem) {
        return _settingsItem->coordinate();
    } else {
        return QGeoCoordinate();
    }
}
DonLakeFlyer's avatar
DonLakeFlyer committed
1641 1642 1643 1644 1645 1646 1647 1648 1649 1650

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);
    }
}
1651 1652 1653 1654 1655 1656 1657 1658 1659 1660 1661 1662 1663

void MissionController::_cameraFeedback(QGeoCoordinate imageCoordinate, int index)
{
    Q_UNUSED(index);
    if (!_editMode) {
        _cameraPoints.append(new QGCQGeoCoordinate(imageCoordinate, this));
    }
}

void MissionController::clearCameraPoints(void)
{
    _cameraPoints.clearAndDeleteContents();
}
1664 1665 1666 1667 1668 1669 1670 1671

void MissionController::_progressPctChanged(double progressPct)
{
    if (!qFuzzyCompare(progressPct, _progressPct)) {
        _progressPct = progressPct;
        emit progressPctChanged(progressPct);
    }
}
1672 1673 1674 1675 1676 1677

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
1678 1679 1680 1681 1682 1683 1684 1685 1686 1687 1688 1689 1690 1691 1692 1693 1694 1695 1696 1697 1698 1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716

bool MissionController::showPlanFromManagerVehicle (void)
{
    qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle";
    if (_masterController->offline()) {
        qCWarning(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
        return true;    // stops further propogation of showPlanFromManagerVehicle due to error
    } 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;
        }
    }
}

void MissionController::_managerSendComplete(void)
{
    // FLy view always reloads on send complete
    if (!_editMode) {
        showPlanFromManagerVehicle();
    }
}

void MissionController::_managerRemoveAllComplete(void)
{
    // Remove all from vehicle so we always update
    showPlanFromManagerVehicle();
}