WimaController.cc 31 KB
Newer Older
Valentin Platzgummer's avatar
Valentin Platzgummer committed
1
#include "WimaController.h"
2

3 4 5 6 7 8 9 10 11 12
const char* WimaController::wimaFileExtension           = "wima";
const char* WimaController::areaItemsName               = "AreaItems";
const char* WimaController::missionItemsName            = "MissionItems";
const char* WimaController::settingsGroup               = "WimaController";
const char* WimaController::enableWimaControllerName    = "EnableWimaController";
const char* WimaController::overlapWaypointsName        = "OverlapWaypoints";
const char* WimaController::maxWaypointsPerPhaseName    = "MaxWaypointsPerPhase";
const char* WimaController::startWaypointIndexName      = "StartWaypointIndex";
const char* WimaController::showAllMissionItemsName     = "ShowAllMissionItems";
const char* WimaController::showCurrentMissionItemsName = "ShowCurrentMissionItems";
13 14
const char* WimaController::flightSpeedName             = "FlightSpeed";
const char* WimaController::altitudeName                = "Altitude";
15

16
WimaController::WimaController(QObject *parent)
17 18 19 20 21 22 23 24 25 26 27
    : QObject                   (parent)
    , _container                (nullptr)
    , _joinedArea               (this)
    , _measurementArea          (this)
    , _serviceArea              (this)
    , _corridor                 (this)
    , _localPlanDataValid       (false)
    , _metaDataMap              (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/WimaController.SettingsGroup.json"), this))
    , _enableWimaController     (settingsGroup, _metaDataMap[enableWimaControllerName])
    , _overlapWaypoints         (settingsGroup, _metaDataMap[overlapWaypointsName])
    , _maxWaypointsPerPhase     (settingsGroup, _metaDataMap[maxWaypointsPerPhaseName])
28
    , _nextPhaseStartWaypointIndex       (settingsGroup, _metaDataMap[startWaypointIndexName])
29
    , _showAllMissionItems      (settingsGroup, _metaDataMap[showAllMissionItemsName])
30 31 32
    , _showCurrentMissionItems  (settingsGroup, _metaDataMap[showCurrentMissionItemsName])    
    , _flightSpeed              (settingsGroup, _metaDataMap[flightSpeedName])
    , _altitude                 (settingsGroup, _metaDataMap[altitudeName])
33
    , _startWaypointIndex       (0)
34
    , _lastMissionPhaseReached  (false)
35
    , _uploadOverrideRequired   (false)
36 37
    , _phaseDistance(-1)
    , _phaseDuration(-1)
38 39
    , _vehicleHasLowBattery(false)
    , _lowBatteryHandlingTriggered(false)
40

41
{
42
    _nextPhaseStartWaypointIndex.setRawValue(int(1));
43 44 45
    _showAllMissionItems.setRawValue(true);
    _showCurrentMissionItems.setRawValue(true);
    connect(&_overlapWaypoints,     &Fact::rawValueChanged, this, &WimaController::updateNextWaypoint);
46
    connect(&_maxWaypointsPerPhase, &Fact::rawValueChanged, this, &WimaController::recalcCurrentPhase);
47
    connect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
48 49
    connect(&_flightSpeed,  &Fact::rawValueChanged, this, &WimaController::updateSpeed);
    connect(&_altitude,     &Fact::rawValueChanged, this, &WimaController::updateAltitude);
50 51 52 53 54 55

    // battery timer
    connect(&_checkBatteryTimer, &QTimer::timeout, this, &WimaController::checkBatteryLevel);

    _checkBatteryTimer.setInterval(500);
    _checkBatteryTimer.start();
56 57
}

58
QmlObjectListModel* WimaController::visualItems()
59
{
60
    return &_visualItems;
61 62
}

Valentin Platzgummer's avatar
Valentin Platzgummer committed
63 64 65 66
QStringList WimaController::loadNameFilters() const
{
    QStringList filters;

67
    filters << tr("Supported types (*.%1 *.%2)").arg(wimaFileExtension).arg(AppSettings::planFileExtension) <<
Valentin Platzgummer's avatar
Valentin Platzgummer committed
68 69
               tr("All Files (*.*)");
    return filters;
70 71 72 73 74
}

QStringList WimaController::saveNameFilters() const
{
    QStringList filters;
Valentin Platzgummer's avatar
Valentin Platzgummer committed
75

76 77
    filters << tr("Supported types (*.%1 *.%2)").arg(wimaFileExtension).arg(AppSettings::planFileExtension);
    return filters;
Valentin Platzgummer's avatar
Valentin Platzgummer committed
78 79
}

80
WimaDataContainer *WimaController::dataContainer()
81
{
82
    return _container;
83 84
}

85 86 87 88 89
QmlObjectListModel *WimaController::missionItems()
{
    return &_missionItems;
}

90 91 92 93 94
QmlObjectListModel *WimaController::currentMissionItems()
{
    return &_currentMissionItems;
}

95 96 97 98 99
QVariantList WimaController::waypointPath()
{
    return  _waypointPath;
}

100 101 102 103 104
QVariantList WimaController::currentWaypointPath()
{
    return _currentWaypointPath;
}

105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129
Fact *WimaController::enableWimaController()
{
    return &_enableWimaController;
}

Fact *WimaController::overlapWaypoints()
{
    return &_overlapWaypoints;
}

Fact *WimaController::maxWaypointsPerPhase()
{
    return &_maxWaypointsPerPhase;
}

Fact *WimaController::showAllMissionItems()
{
    return &_showAllMissionItems;
}

Fact *WimaController::showCurrentMissionItems()
{
    return &_showCurrentMissionItems;
}

130 131 132 133 134 135 136 137 138 139
Fact *WimaController::flightSpeed()
{
    return &_flightSpeed;
}

Fact *WimaController::altitude()
{
    return &_altitude;
}

140 141 142 143 144
bool WimaController::uploadOverrideRequired() const
{
    return _uploadOverrideRequired;
}

145 146 147 148 149 150 151 152 153 154
double WimaController::phaseDistance() const
{
    return _phaseDistance;
}

double WimaController::phaseDuration() const
{
    return _phaseDuration;
}

155 156 157 158 159
bool WimaController::vehicleHasLowBattery() const
{
    return _vehicleHasLowBattery;
}

160 161
Fact *WimaController::startWaypointIndex()
{
162
    return &_nextPhaseStartWaypointIndex;
163 164
}

165 166 167 168 169 170 171 172 173 174 175 176
void WimaController::setMasterController(PlanMasterController *masterC)
{
    _masterController = masterC;
    emit masterControllerChanged();
}

void WimaController::setMissionController(MissionController *missionC)
{
    _missionController = missionC;
    emit missionControllerChanged();
}

177 178 179 180 181 182
/*!
 * \fn void WimaController::setDataContainer(WimaDataContainer *container)
 * Sets the pointer to the \c WimaDataContainer, which is meant to exchange data between the \c WimaController and the \c WimaPlaner.
 *
 * \sa WimaPlaner, WimaDataContainer, WimaPlanData
 */
183 184
void WimaController::setDataContainer(WimaDataContainer *container)
{
185 186
    if (container != nullptr) {
        if (_container != nullptr) {
187
           disconnect(_container, &WimaDataContainer::newDataAvailable, this, &WimaController::fetchContainerData);
188 189
        }

190
        _container = container;
191
        connect(_container, &WimaDataContainer::newDataAvailable, this, &WimaController::fetchContainerData);
192 193 194 195 196

        emit dataContainerChanged();
    }
}

197 198 199 200 201 202 203 204 205
void WimaController::setUploadOverrideRequired(bool overrideRequired)
{
    if (_uploadOverrideRequired != overrideRequired) {
        _uploadOverrideRequired = overrideRequired;

        emit uploadOverrideRequiredChanged();
    }
}

206 207
void WimaController::nextPhase()
{
208
    calcNextPhase();
209 210
}

211 212
void WimaController::previousPhase()
{
213 214
    if (_nextPhaseStartWaypointIndex.rawValue().toInt() > 0) {
        _lastMissionPhaseReached = false;
215 216 217
        _nextPhaseStartWaypointIndex.setRawValue(std::max(_startWaypointIndex
                                                          - _maxWaypointsPerPhase.rawValue().toInt()
                                                          + _overlapWaypoints.rawValue().toInt(), 1));
218
    }
219 220 221 222
}

void WimaController::resetPhase()
{
223 224
    _lastMissionPhaseReached = false;
    _nextPhaseStartWaypointIndex.setRawValue(int(1));
225 226
}

227
bool WimaController::uploadToVehicle()
228
{
229 230
    if (   !_serviceArea.containsCoordinate(_masterController->managerVehicle()->coordinate())
        && _currentMissionItems.count() > 0) {
231 232 233 234 235 236 237 238 239 240
        setUploadOverrideRequired(true);
        return false;
    }

    return forceUploadToVehicle();
}

bool WimaController::forceUploadToVehicle()
{
    setUploadOverrideRequired(false);
241
    if (_currentMissionItems.count() < 1)
242
        return false;
243 244 245 246 247 248 249

    _missionController->removeAll();
    // set homeposition of settingsItem
    QmlObjectListModel* visuals = _missionController->visualItems();
    MissionSettingsItem* settingsItem = visuals->value<MissionSettingsItem *>(0);
    if (settingsItem == nullptr) {
        qWarning("WimaController::updateCurrentMissionItems(): nullptr");
250
        return false;
251 252 253 254 255 256 257 258 259
    }
    settingsItem->setCoordinate(_takeoffLandPostion);

    // copy mission items from _currentMissionItems to _missionController
    for (int i = 0; i < _currentMissionItems.count(); i++){
        SimpleMissionItem *item = _currentMissionItems.value<SimpleMissionItem *>(i);
        _missionController->insertSimpleMissionItem(*item, visuals->count());
    }

260
    _masterController->sendToVehicle();
261 262

    return true;
263
}
264

265 266 267
void WimaController::removeFromVehicle()
{
    _masterController->removeAllFromVehicle();
268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290
    _missionController->removeAll();
}

bool WimaController::checkSmartRTLPreCondition()
{
    QString errorString;
    bool retValue = _checkSmartRTLPreCondition(errorString);
    if (retValue == false) {
        qgcApp()->showMessage(errorString);
        return false;
    }
    return true;
}

bool WimaController::calcReturnPath()
{
    QString errorString;
    bool retValue = _calcReturnPath(errorString);
    if (retValue == false) {
        qgcApp()->showMessage(errorString);
        return false;
    }
    return true;
291 292
}

293
void WimaController::saveToCurrent()
294
{
295

296 297
}

298 299
void WimaController::saveToFile(const QString& filename)
{
300
    QString file = filename;
301 302
}

303
bool WimaController::loadFromCurrent()
304
{
305
    return true;
306 307 308 309
}

bool WimaController::loadFromFile(const QString &filename)
{
310
    QString file = filename;
311
    return true;
312 313 314
}


315

316
QJsonDocument WimaController::saveToJson(FileType fileType)
317
{
318 319 320 321
    if(fileType)
    {

    }
322
    return QJsonDocument();
323 324
}

325 326 327 328 329 330 331 332 333 334 335 336 337 338 339
bool WimaController::calcShortestPath(const QGeoCoordinate &start, const QGeoCoordinate &destination, QList<QGeoCoordinate> &path)
{
    using namespace GeoUtilities;
    using namespace PolygonCalculus;
    QList<QPointF> path2D;
    bool retVal = PolygonCalculus::shortestPath(
                                   toQPolygonF(toCartesian2D(_joinedArea.coordinateList(), /*origin*/ start)),
                                   /*start point*/ QPointF(0,0),
                                   /*destination*/ toCartesian2D(destination, start),
                                   /*shortest path*/ path2D);
    path.append(toGeo(path2D, /*origin*/ start));

    return  retVal;
}

340
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList)
341 342 343 344
{
    return extractCoordinateList(missionItems, coordinateList, 0, missionItems.count()-1);
}

345
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList, int startIndex, int endIndex)
346 347 348 349 350 351 352 353 354 355 356 357
{
    if (   startIndex >= 0
        && startIndex < missionItems.count()
        && endIndex >= 0
        && endIndex < missionItems.count()) {
        if (startIndex > endIndex) {
            if (!extractCoordinateList(missionItems, coordinateList, startIndex, missionItems.count()-1))
                return false;
            if (!extractCoordinateList(missionItems, coordinateList, 0, endIndex))
                return false;
        } else {
            for (int i = startIndex; i <= endIndex; i++) {
358
                SimpleMissionItem *mItem = missionItems.value<SimpleMissionItem *>(i);
359 360 361 362 363 364 365 366 367 368 369 370 371 372

                if (mItem == nullptr) {
                    coordinateList.clear();
                    return false;
                }
                coordinateList.append(mItem->coordinate());
            }
        }
    } else
        return false;

    return true;
}

373
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList)
374 375 376 377
{
    return extractCoordinateList(missionItems, coordinateList, 0 , missionItems.count()-1);
}

378
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList, int startIndex, int endIndex)
379 380 381 382 383
{
    QList<QGeoCoordinate> geoCoordintateList;

    bool retValue = extractCoordinateList(missionItems, geoCoordintateList, startIndex, endIndex);

384 385 386
    if (!retValue)
        return false;

387 388 389 390 391 392
    for (int i = 0; i < geoCoordintateList.size(); i++) {
        QGeoCoordinate vertex = geoCoordintateList[i];
        if (qFuzzyIsNull(vertex.latitude()) && qFuzzyIsNull(vertex.longitude()))
            geoCoordintateList.removeAt(i);
    }

393 394 395 396 397 398
    for (auto coordinate : geoCoordintateList)
        coordinateList.append(QVariant::fromValue(coordinate));

    return true;
}

399 400 401 402 403 404 405
/*!
 * \fn void WimaController::containerDataValidChanged(bool valid)
 * Pulls plan data generated by \c WimaPlaner from the \c _container if the data is valid (\a valid equals true).
 * Is connected to the dataValidChanged() signal of the \c WimaDataContainer.
 *
 * \sa WimaDataContainer, WimaPlaner, WimaPlanData
 */
406
bool WimaController::fetchContainerData()
407
{
408
    // fetch only if valid, return true on sucess
409

410 411
    // reset visual items
    _visualItems.clear();
412 413
    _missionItems.clearAndDeleteContents();
    _currentMissionItems.clearAndDeleteContents();
414 415
    _waypointPath.clear();
    _currentWaypointPath.clear();
416

417 418 419 420
    emit visualItemsChanged();
    emit missionItemsChanged();
    emit currentMissionItemsChanged();
    emit currentWaypointPathChanged();
421

422 423
    _localPlanDataValid = false;
    _lastMissionPhaseReached = false;
424

425 426 427 428
    if (_container == nullptr) {
        qWarning("WimaController::fetchContainerData(): No container assigned!");
        return false;
    }
429

430
    WimaPlanData planData = _container->pull();
431

432 433
    // extract list with WimaAreas
    QList<const WimaAreaData*> areaList = planData.areaList();
434

435 436 437 438
    int areaCounter = 0;
    int numAreas = 4; // extract only numAreas Areas, if there are more they are invalid and ignored
    for (int i = 0; i < areaList.size(); i++) {
        const WimaAreaData *areaData = areaList[i];
439

440 441 442 443
        if (areaData->type() == WimaServiceAreaData::typeString) { // is it a service area?
            _serviceArea = *qobject_cast<const WimaServiceAreaData*>(areaData);
            areaCounter++;
            _visualItems.append(&_serviceArea);
444

445 446
            continue;
        }
447

448 449 450 451
        if (areaData->type() == WimaMeasurementAreaData::typeString) { // is it a measurement area?
            _measurementArea =  *qobject_cast<const WimaMeasurementAreaData*>(areaData);
            areaCounter++;
            _visualItems.append(&_measurementArea);
452

453
            continue;
454
        }
455

456 457 458 459
        if (areaData->type() == WimaCorridorData::typeString) { // is it a corridor?
            _corridor =  *qobject_cast<const WimaCorridorData*>(areaData);
            areaCounter++;
            //_visualItems.append(&_corridor); // not needed
460

461 462
            continue;
        }
463

464 465 466 467
        if (areaData->type() == WimaJoinedAreaData::typeString) { // is it a corridor?
            _joinedArea =  *qobject_cast<const WimaJoinedAreaData*>(areaData);
            areaCounter++;
            _visualItems.append(&_joinedArea);
468

469 470
            continue;
        }
471

472 473 474
        if (areaCounter >= numAreas)
            break;
    }
475

476
    // extract mission items
477
    QList<MissionItem> tempMissionItems = planData.missionItems();
478 479
    if (tempMissionItems.size() < 1)
        return false;
480

481 482 483 484 485 486
    // create mission items
    _missionController->removeAll();
    QmlObjectListModel* missionControllerVisualItems = _missionController->visualItems();

    // create SimpleMissionItem by using _missionController
    for ( int i = 0; i < tempMissionItems.size(); i++) {
487
        _missionController->insertSimpleMissionItem(tempMissionItems[i], missionControllerVisualItems->count());
488 489 490 491 492 493 494
    }
    // copy mission items from _missionController to _missionItems
    for ( int i = 1; i < missionControllerVisualItems->count(); i++) {
        SimpleMissionItem *visualItem     = qobject_cast<SimpleMissionItem *>((*missionControllerVisualItems)[i]);
        if (visualItem == nullptr) {
            qWarning("WimaController::fetchContainerData(): Nullptr at SimpleMissionItem!");
            return false;
495
        }
496 497 498 499 500
        SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
        _missionItems.append(visualItemCopy);
    }
    if (areaCounter != numAreas)
        return false;
501

502 503
    if (!setTakeoffLandPosition())
        return false;
504

505
    updateWaypointPath();
506

507 508 509 510
    // set _nextPhaseStartWaypointIndex to 1
    disconnect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
    _nextPhaseStartWaypointIndex.setRawValue(int(1));
    connect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
511

512 513
    if(!calcNextPhase())
        return false;
514

515

516 517

    emit visualItemsChanged();
518
    emit missionItemsChanged();
519

520 521 522

    _localPlanDataValid = true;
    return true;
523 524
}

525
bool WimaController::calcNextPhase()
526
{
527 528 529
    if (_missionItems.count() < 1 || _lastMissionPhaseReached)
        return false;

530
    _currentMissionItems.clearAndDeleteContents();
531 532 533 534 535 536 537 538
    _currentWaypointPath.clear();
    emit currentMissionItemsChanged();
    emit currentWaypointPathChanged();

    _startWaypointIndex = _nextPhaseStartWaypointIndex.rawValue().toInt()-1;
    if (_startWaypointIndex > _missionItems.count()-1)
        return false;

539

540 541 542
    int maxWaypointsPerPhaseInt = _maxWaypointsPerPhase.rawValue().toInt();

    // determine end waypoint index
543 544 545
    _endWaypointIndex = std::min(_startWaypointIndex + maxWaypointsPerPhaseInt - 1, _missionItems.count()-1);
    if (_endWaypointIndex == _missionItems.count() - 1)
        _lastMissionPhaseReached = true;
546

547
    // extract waypoints
548
    QList<QGeoCoordinate> geoCoordinateList; // list with potential waypoints (from _missionItems), for _currentMissionItems
549
    if (!extractCoordinateList(_missionItems, geoCoordinateList, _startWaypointIndex, _endWaypointIndex)) {
550 551
        qWarning("WimaController::calcNextPhase(): error on waypoint extraction.");
        return false;
552
    }
553 554

    // set start waypoint index for next phase
555 556 557 558 559 560
    if (!_lastMissionPhaseReached) {
        disconnect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
        int untruncated = std::max(_endWaypointIndex + 1 - _overlapWaypoints.rawValue().toInt(), 0);
        int truncated   = std::min(untruncated , _missionItems.count()-1);
        _nextPhaseStartWaypointIndex.setRawValue(truncated  + 1);
        connect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
561
    }
562 563 564

    // calculate path from home to first waypoint
    QList<QGeoCoordinate> path;
565 566 567 568
    if (!_takeoffLandPostion.isValid()){
        qWarning("WimaController::calcNextPhase(): _takeoffLandPostion not valid.");
        return false;
    }
569
    if ( !calcShortestPath(_takeoffLandPostion, geoCoordinateList[0], path) ) {
570 571
        qWarning("WimaController::calcNextPhase(): Not able to calc path from home to first waypoint.");
        return false;
572 573 574 575 576 577 578
    }
    // prepend to geoCoordinateList
    for (int i = path.size()-2; i >= 0; i--) //  i = path.size()-2 : last coordinate already in geoCoordinateList
        geoCoordinateList.prepend(path[i]);

    // calculate path from last waypoint to home
    path.clear();
579
    if ( !calcShortestPath(geoCoordinateList.last(), _takeoffLandPostion, path) ) {
580 581
        qWarning("WimaController::calcNextPhase(): Not able to calc path from home to first waypoint.");
        return false;
582 583 584 585
    }
    path.removeFirst(); // first coordinate already in geoCoordinateList
    geoCoordinateList.append(path);

586

587 588 589
    // create Mission Items
    _missionController->removeAll();
    QmlObjectListModel* missionControllerVisuals = _missionController->visualItems();
590 591 592 593

    // set homeposition of settingsItem
    MissionSettingsItem* settingsItem = missionControllerVisuals->value<MissionSettingsItem *>(0);
    if (settingsItem == nullptr) {
594 595
        qWarning("WimaController::calcNextPhase(): nullptr");
        return false;
596 597 598 599
    }
    settingsItem->setCoordinate(_takeoffLandPostion);

    for (auto coordinate : geoCoordinateList) {
600
        _missionController->insertSimpleMissionItem(coordinate, missionControllerVisuals->count());
601 602
    }

603 604 605 606 607
    // set takeoff position for first mission item (bug)
    SimpleMissionItem *takeoffItem = missionControllerVisuals->value<SimpleMissionItem*>(1);
    if (takeoffItem == nullptr) {
        qWarning("WimaController::calcNextPhase(): nullptr");
        return false;
608
    }
609
    takeoffItem->setCoordinate(_takeoffLandPostion);
610

611 612 613 614 615 616 617 618 619 620 621
    // create change speed item
    _missionController->insertSimpleMissionItem(_takeoffLandPostion, 2);
    SimpleMissionItem *speedItem = missionControllerVisuals->value<SimpleMissionItem*>(2);
    if (speedItem == nullptr) {
        qWarning("WimaController::calcNextPhase(): nullptr");
        return false;
    }
    speedItem->setCoordinate(_takeoffLandPostion);
    speedItem->setCommand(MAV_CMD_DO_CHANGE_SPEED);
    speedItem->missionItem().setParam2(_flightSpeed.rawValue().toDouble());

622 623 624 625

    // set land command for last mission item
    SimpleMissionItem *landItem = missionControllerVisuals->value<SimpleMissionItem*>(missionControllerVisuals->count()-1);
    if (landItem == nullptr) {
626 627
        qWarning("WimaController::calcNextPhase(): nullptr");
        return false;
628
    }
629
    _missionController->setLandCommand(*landItem);
630

631
    // copy to _currentMissionItems
632 633 634
    for ( int i = 1; i < missionControllerVisuals->count(); i++) {
        SimpleMissionItem *visualItem     = missionControllerVisuals->value<SimpleMissionItem*>(i);
        if (visualItem == nullptr) {
635
            qWarning("WimaController::calcNextPhase(): Nullptr at SimpleMissionItem!");
636
            _currentMissionItems.clear();
637
            return false;
638
        }
639

640
        SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
641 642
        _currentMissionItems.append(visualItemCopy);
    }
643

644 645
    _setPhaseDistance(_missionController->missionDistance());
    _setPhaseDuration(_missionController->missionDistance()/_flightSpeed.rawValue().toDouble());
646
    _missionController->removeAll(); // remove items from _missionController, will be added on upload
647
    updateAltitude();
648

649
    updateCurrentPath();
650
    emit currentMissionItemsChanged();
651 652

    return true;
653
}
654

655 656 657
void WimaController::updateWaypointPath()
{
    _waypointPath.clear();
658
    extractCoordinateList(_missionItems, _waypointPath, 0, _missionItems.count()-1);
659

660 661 662 663 664
    emit waypointPathChanged();
}
void WimaController::updateCurrentPath()
{
    _currentWaypointPath.clear();
665
    extractCoordinateList(_currentMissionItems, _currentWaypointPath, 0, _currentMissionItems.count()-1);
666

667 668
    emit currentWaypointPathChanged();
}
669

670 671 672
void WimaController::updateNextWaypoint()
{
    if (_endWaypointIndex < _missionItems.count()-2) {
673 674 675
        disconnect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
        _nextPhaseStartWaypointIndex.setRawValue(1 + std::max(_endWaypointIndex + 1 - _overlapWaypoints.rawValue().toInt(), 0));
        connect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
676 677 678
    }
}

679 680
void WimaController::recalcCurrentPhase()
{
681
    _lastMissionPhaseReached = false;
682 683 684 685
    disconnect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
    _nextPhaseStartWaypointIndex.setRawValue(_startWaypointIndex + 1);    
    connect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
    calcNextPhase();
686 687 688 689 690 691 692 693 694
}

bool WimaController::setTakeoffLandPosition()
{
    _takeoffLandPostion.setAltitude(0);
    _takeoffLandPostion.setLongitude(_serviceArea.center().longitude());
    _takeoffLandPostion.setLatitude(_serviceArea.center().latitude());

    return true;
695 696
}

697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720
void WimaController::updateSpeed()
{
    SimpleMissionItem *item = _currentMissionItems.value<SimpleMissionItem *>(1); // speed item
    if (item != nullptr && item->command() == MAV_CMD_DO_CHANGE_SPEED) {
        item->missionItem().setParam2(_flightSpeed.rawValue().toDouble());
        _setPhaseDuration(_phaseDistance/_flightSpeed.rawValue().toDouble());
    }
    else {
        qWarning("WimaController::updateSpeed(): internal error.");
    }
}

void WimaController::updateAltitude()
{
    for (int i = 0; i < _currentMissionItems.count(); i++) {
        SimpleMissionItem *item = _currentMissionItems.value<SimpleMissionItem *>(i);
        if (item == nullptr) {
            qWarning("WimaController::updateAltitude(): nullptr");
            return;
        }
        item->altitude()->setRawValue(_altitude.rawValue().toDouble());
    }
}

721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754
void WimaController::checkBatteryLevel()
{
    Vehicle *managerVehicle = masterController()->managerVehicle();
    int batteryThreshold = 94; // percent
    if (managerVehicle != nullptr) {
        Fact *battery1percentRemaining = managerVehicle->battery1FactGroup()->getFact(VehicleBatteryFactGroup::_percentRemainingFactName);
        Fact *battery2percentRemaining = managerVehicle->battery2FactGroup()->getFact(VehicleBatteryFactGroup::_percentRemainingFactName);


        if (battery1percentRemaining->rawValue().toDouble() < batteryThreshold
                && battery2percentRemaining->rawValue().toDouble() < batteryThreshold) {
            _setVehicleHasLowBattery(true);
            if (!_lowBatteryHandlingTriggered) {
                QString errorString;
                if (_checkSmartRTLPreCondition(errorString) == true) {
                    managerVehicle->pauseVehicle();
                    if (_calcReturnPath(errorString)) {
                        emit returnBatteryLowConfirmRequired();
                    } else {
                        qgcApp()->showMessage(tr("Battery level is low. Smart RTL not possible."));
                        qgcApp()->showMessage(errorString);
                    }
                }
                _lowBatteryHandlingTriggered = true;
            }
        }
        else {
            _setVehicleHasLowBattery(false);
            _lowBatteryHandlingTriggered = false;
        }

    }
}

755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772
void WimaController::_setPhaseDistance(double distance)
{
    if (!qFuzzyCompare(distance, _phaseDistance)) {
        _phaseDistance = distance;

        emit phaseDistanceChanged();
    }
}

void WimaController::_setPhaseDuration(double duration)
{
    if (!qFuzzyCompare(duration, _phaseDuration)) {
        _phaseDuration = duration;

        emit phaseDurationChanged();
    }
}

773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910
bool WimaController::_checkSmartRTLPreCondition(QString &errorString)
{
    if (!_localPlanDataValid) {
        errorString.append(tr("No WiMA data available. Please define at least a measurement and a service area."));
        return false;
    }
    Vehicle *managerVehicle = masterController()->managerVehicle();
   if (!managerVehicle->flying()) {
        errorString.append(tr("Vehicle is not flying. Smart RTL not available."));
        return false;
   }
}

bool WimaController::_calcReturnPath(QString &errorSring)
{
    // it is assumed that checkSmartRTLPreCondition() was called first and true was returned


    Vehicle *managerVehicle = masterController()->managerVehicle();

    QGeoCoordinate currentVehiclePosition = managerVehicle->coordinate();
    // check if vehicle inside _joinedArea, this statement is not inside checkSmartRTLPreCondition() because during checkSmartRTLPreCondition() vehicle is not paused yet
    if (!_joinedArea.containsCoordinate(currentVehiclePosition)) {
        errorSring.append(tr("Vehicle not inside joined area. Action not supported."));
        return false;
    }

    // calculate return path
    QList<QGeoCoordinate> returnPath;
    calcShortestPath(currentVehiclePosition, _takeoffLandPostion, returnPath);
    // successful?
    if (returnPath.isEmpty()) {
        errorSring.append(tr("Not able to calculate return path."));
        return false;
    }
    // qWarning() << "returnPath.size()" << returnPath.size();

    // buffer _currentMissionItems
    //qWarning() << "_currentMissionItems.count()" << _currentMissionItems.count();
    //qWarning() << "_missionItemsBuffer.count()" << _missionItemsBuffer.count();
    _missionItemsBuffer.clear();
    int numCurrentMissionItems = _currentMissionItems.count();
    for (int i = 0; i < numCurrentMissionItems; i++)
        _missionItemsBuffer.append(_currentMissionItems.removeAt(0));
    //qWarning() << "_currentMissionItems.count()" << _currentMissionItems.count();
    //qWarning() << "_missionItemsBuffer.count()" << _missionItemsBuffer.count();

    // create Mission Items
    removeFromVehicle();
    QmlObjectListModel* missionControllerVisuals = _missionController->visualItems();

    // set homeposition of settingsItem
    MissionSettingsItem* settingsItem = missionControllerVisuals->value<MissionSettingsItem *>(0);
    if (settingsItem == nullptr) {
        qWarning("WimaController: nullptr");
        return false;
    }
    settingsItem->setCoordinate(_takeoffLandPostion);

    // copy from returnPath to _missionController
    QGeoCoordinate speedItemCoordinate = returnPath.first();
    for (auto coordinate : returnPath) {
        _missionController->insertSimpleMissionItem(coordinate, missionControllerVisuals->count());
    }
    //qWarning() << "missionControllerVisuals->count()" << missionControllerVisuals->count();

    // create speed item
    int speedItemIndex = 1;
    _missionController->insertSimpleMissionItem(speedItemCoordinate, speedItemIndex);
    SimpleMissionItem *speedItem = missionControllerVisuals->value<SimpleMissionItem*>(speedItemIndex);
    if (speedItem == nullptr) {
        qWarning("WimaController: nullptr");
        return false;
    }
    speedItem->setCoordinate(speedItemCoordinate);
    speedItem->setCommand(MAV_CMD_DO_CHANGE_SPEED);
    speedItem->missionItem().setParam2(_flightSpeed.rawValue().toDouble());

    // set second item command to ordinary waypoint (is takeoff)
    SimpleMissionItem *secondItem = missionControllerVisuals->value<SimpleMissionItem*>(2);
    if (secondItem == nullptr) {
        qWarning("WimaController: nullptr");
        return false;
    }
    secondItem->setCoordinate(speedItemCoordinate);
    secondItem->setCommand(MAV_CMD_NAV_WAYPOINT);


    // set land command for last mission item
    SimpleMissionItem *landItem = missionControllerVisuals->value<SimpleMissionItem*>(missionControllerVisuals->count()-1);
    if (landItem == nullptr) {
        qWarning("WimaController: nullptr");
        return false;
    }
    _missionController->setLandCommand(*landItem);

    // copy to _currentMissionItems
    //qWarning() << "_currentMissionItems.count()" << _currentMissionItems.count();
    for ( int i = 1; i < missionControllerVisuals->count(); i++) {
        SimpleMissionItem *visualItem     = missionControllerVisuals->value<SimpleMissionItem*>(i);
        if (visualItem == nullptr) {
            qWarning("WimaController: Nullptr at SimpleMissionItem!");
            _currentMissionItems.clear();
            return false;
        }

        SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
        _currentMissionItems.append(visualItemCopy);
    }
    //qWarning() << "_currentMissionItems.count()" << _currentMissionItems.count();

    _setPhaseDistance(_missionController->missionDistance());
    _setPhaseDuration(_missionController->missionDistance()/_flightSpeed.rawValue().toDouble());
    _missionController->removeAll(); // remove items from _missionController, will be added on upload
    updateAltitude();

    updateCurrentPath();
    emit currentMissionItemsChanged();


    //qWarning() << "_currentMissionItems.count()" << _currentMissionItems.count();
    _showAllMissionItems.setRawValue(false);
    managerVehicle->trajectoryPoints()->clear();

    emit uploadAndExecuteConfirmRequired();
    return true;
}

void WimaController::_setVehicleHasLowBattery(bool batteryLow)
{
    if (_vehicleHasLowBattery != batteryLow) {
        _vehicleHasLowBattery = batteryLow;

        emit vehicleHasLowBatteryChanged();
        qWarning() << "WimaController::_setVehicleHasLowBattery(bool batteryLow)" << _vehicleHasLowBattery;
    }
}

911 912