WimaController.cc 23.2 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
{
40
    _nextPhaseStartWaypointIndex.setRawValue(int(1));
41 42 43
    _showAllMissionItems.setRawValue(true);
    _showCurrentMissionItems.setRawValue(true);
    connect(&_overlapWaypoints,     &Fact::rawValueChanged, this, &WimaController::updateNextWaypoint);
44
    connect(&_maxWaypointsPerPhase, &Fact::rawValueChanged, this, &WimaController::recalcCurrentPhase);
45
    connect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
46 47
    connect(&_flightSpeed,  &Fact::rawValueChanged, this, &WimaController::updateSpeed);
    connect(&_altitude,     &Fact::rawValueChanged, this, &WimaController::updateAltitude);
48 49
}

50
QmlObjectListModel* WimaController::visualItems()
51
{
52
    return &_visualItems;
53 54
}

Valentin Platzgummer's avatar
Valentin Platzgummer committed
55 56 57 58
QStringList WimaController::loadNameFilters() const
{
    QStringList filters;

59
    filters << tr("Supported types (*.%1 *.%2)").arg(wimaFileExtension).arg(AppSettings::planFileExtension) <<
Valentin Platzgummer's avatar
Valentin Platzgummer committed
60 61
               tr("All Files (*.*)");
    return filters;
62 63 64 65 66
}

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

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

72
WimaDataContainer *WimaController::dataContainer()
73
{
74
    return _container;
75 76
}

77 78 79 80 81
QmlObjectListModel *WimaController::missionItems()
{
    return &_missionItems;
}

82 83 84 85 86
QmlObjectListModel *WimaController::currentMissionItems()
{
    return &_currentMissionItems;
}

87 88 89 90 91
QVariantList WimaController::waypointPath()
{
    return  _waypointPath;
}

92 93 94 95 96
QVariantList WimaController::currentWaypointPath()
{
    return _currentWaypointPath;
}

97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121
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;
}

122 123 124 125 126 127 128 129 130 131
Fact *WimaController::flightSpeed()
{
    return &_flightSpeed;
}

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

132 133 134 135 136
bool WimaController::uploadOverrideRequired() const
{
    return _uploadOverrideRequired;
}

137 138 139 140 141 142 143 144 145 146
double WimaController::phaseDistance() const
{
    return _phaseDistance;
}

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

147 148
Fact *WimaController::startWaypointIndex()
{
149
    return &_nextPhaseStartWaypointIndex;
150 151
}

152 153 154 155 156 157 158 159 160 161 162 163
void WimaController::setMasterController(PlanMasterController *masterC)
{
    _masterController = masterC;
    emit masterControllerChanged();
}

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

164 165 166 167 168 169
/*!
 * \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
 */
170 171
void WimaController::setDataContainer(WimaDataContainer *container)
{
172 173
    if (container != nullptr) {
        if (_container != nullptr) {
174
           disconnect(_container, &WimaDataContainer::newDataAvailable, this, &WimaController::fetchContainerData);
175 176
        }

177
        _container = container;
178
        connect(_container, &WimaDataContainer::newDataAvailable, this, &WimaController::fetchContainerData);
179 180 181 182 183

        emit dataContainerChanged();
    }
}

184 185 186 187 188 189 190 191 192
void WimaController::setUploadOverrideRequired(bool overrideRequired)
{
    if (_uploadOverrideRequired != overrideRequired) {
        _uploadOverrideRequired = overrideRequired;

        emit uploadOverrideRequiredChanged();
    }
}

193 194
void WimaController::nextPhase()
{
195
    calcNextPhase();
196 197
}

198 199
void WimaController::previousPhase()
{
200 201
    if (_nextPhaseStartWaypointIndex.rawValue().toInt() > 0) {
        _lastMissionPhaseReached = false;
202 203 204
        _nextPhaseStartWaypointIndex.setRawValue(std::max(_startWaypointIndex
                                                          - _maxWaypointsPerPhase.rawValue().toInt()
                                                          + _overlapWaypoints.rawValue().toInt(), 1));
205
    }
206 207 208 209
}

void WimaController::resetPhase()
{
210 211
    _lastMissionPhaseReached = false;
    _nextPhaseStartWaypointIndex.setRawValue(int(1));
212 213
}

214
bool WimaController::uploadToVehicle()
215
{
216 217
    if (   !_serviceArea.containsCoordinate(_masterController->managerVehicle()->coordinate())
        && _currentMissionItems.count() > 0) {
218 219 220 221 222 223 224 225 226 227
        setUploadOverrideRequired(true);
        return false;
    }

    return forceUploadToVehicle();
}

bool WimaController::forceUploadToVehicle()
{
    setUploadOverrideRequired(false);
228
    if (_currentMissionItems.count() < 1)
229
        return false;
230 231 232 233 234 235 236

    _missionController->removeAll();
    // set homeposition of settingsItem
    QmlObjectListModel* visuals = _missionController->visualItems();
    MissionSettingsItem* settingsItem = visuals->value<MissionSettingsItem *>(0);
    if (settingsItem == nullptr) {
        qWarning("WimaController::updateCurrentMissionItems(): nullptr");
237
        return false;
238 239 240 241 242 243 244 245 246
    }
    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());
    }

247
    _masterController->sendToVehicle();
248 249

    return true;
250
}
251

252 253 254
void WimaController::removeFromVehicle()
{
    _masterController->removeAllFromVehicle();
255 256
}

257
void WimaController::saveToCurrent()
258
{
259

260 261
}

262 263
void WimaController::saveToFile(const QString& filename)
{
264
    QString file = filename;
265 266
}

267
bool WimaController::loadFromCurrent()
268
{
269
    return true;
270 271 272 273
}

bool WimaController::loadFromFile(const QString &filename)
{
274
    QString file = filename;
275
    return true;
276 277 278
}


279

280
QJsonDocument WimaController::saveToJson(FileType fileType)
281
{
282 283 284 285
    if(fileType)
    {

    }
286
    return QJsonDocument();
287 288
}

289 290 291 292 293 294 295 296 297 298 299 300 301 302 303
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;
}

304
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList)
305 306 307 308
{
    return extractCoordinateList(missionItems, coordinateList, 0, missionItems.count()-1);
}

309
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList, int startIndex, int endIndex)
310 311 312 313 314 315 316 317 318 319 320 321
{
    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++) {
322
                SimpleMissionItem *mItem = missionItems.value<SimpleMissionItem *>(i);
323 324 325 326 327 328 329 330 331 332 333 334 335 336

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

    return true;
}

337
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList)
338 339 340 341
{
    return extractCoordinateList(missionItems, coordinateList, 0 , missionItems.count()-1);
}

342
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList, int startIndex, int endIndex)
343 344 345 346 347
{
    QList<QGeoCoordinate> geoCoordintateList;

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

348 349 350 351 352 353
    for (int i = 0; i < geoCoordintateList.size(); i++) {
        QGeoCoordinate vertex = geoCoordintateList[i];
        if (qFuzzyIsNull(vertex.latitude()) && qFuzzyIsNull(vertex.longitude()))
            geoCoordintateList.removeAt(i);
    }

354 355 356 357 358 359 360 361 362
    if (!retValue)
        return false;

    for (auto coordinate : geoCoordintateList)
        coordinateList.append(QVariant::fromValue(coordinate));

    return true;
}

363 364 365 366 367 368 369
/*!
 * \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
 */
370
bool WimaController::fetchContainerData()
371
{
372
    // fetch only if valid, return true on sucess
373

374 375 376 377 378 379
    // reset visual items
    _visualItems.clear();
    _missionItems.clear();
    _currentMissionItems.clear();
    _waypointPath.clear();
    _currentWaypointPath.clear();
380

381 382 383 384
    emit visualItemsChanged();
    emit missionItemsChanged();
    emit currentMissionItemsChanged();
    emit currentWaypointPathChanged();
385

386 387
    _localPlanDataValid = false;
    _lastMissionPhaseReached = false;
388

389 390 391 392
    if (_container == nullptr) {
        qWarning("WimaController::fetchContainerData(): No container assigned!");
        return false;
    }
393

394
    WimaPlanData planData = _container->pull();
395

396 397
    // extract list with WimaAreas
    QList<const WimaAreaData*> areaList = planData.areaList();
398

399 400 401 402
    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];
403

404 405 406 407
        if (areaData->type() == WimaServiceAreaData::typeString) { // is it a service area?
            _serviceArea = *qobject_cast<const WimaServiceAreaData*>(areaData);
            areaCounter++;
            _visualItems.append(&_serviceArea);
408

409 410
            continue;
        }
411

412 413 414 415
        if (areaData->type() == WimaMeasurementAreaData::typeString) { // is it a measurement area?
            _measurementArea =  *qobject_cast<const WimaMeasurementAreaData*>(areaData);
            areaCounter++;
            _visualItems.append(&_measurementArea);
416

417
            continue;
418
        }
419

420 421 422 423
        if (areaData->type() == WimaCorridorData::typeString) { // is it a corridor?
            _corridor =  *qobject_cast<const WimaCorridorData*>(areaData);
            areaCounter++;
            //_visualItems.append(&_corridor); // not needed
424

425 426
            continue;
        }
427

428 429 430 431
        if (areaData->type() == WimaJoinedAreaData::typeString) { // is it a corridor?
            _joinedArea =  *qobject_cast<const WimaJoinedAreaData*>(areaData);
            areaCounter++;
            _visualItems.append(&_joinedArea);
432

433 434
            continue;
        }
435

436 437 438
        if (areaCounter >= numAreas)
            break;
    }
439

440 441 442 443
    // extract mission items
    QList<const MissionItem*> tempMissionItems = planData.missionItems();
    if (tempMissionItems.size() < 1)
        return false;
444

445 446 447 448 449 450 451 452 453 454 455 456 457 458 459
    // create mission items
    _missionController->removeAll();
    QmlObjectListModel* missionControllerVisualItems = _missionController->visualItems();

    // create SimpleMissionItem by using _missionController
    for ( int i = 0; i < tempMissionItems.size(); i++) {
        const MissionItem *missionItem = tempMissionItems[i];
        _missionController->insertSimpleMissionItem(*missionItem, missionControllerVisualItems->count());
    }
    // 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;
460
        }
461 462 463 464 465
        SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
        _missionItems.append(visualItemCopy);
    }
    if (areaCounter != numAreas)
        return false;
466

467 468
    if (!setTakeoffLandPosition())
        return false;
469

470
    updateWaypointPath();
471

472 473 474 475
    // set _nextPhaseStartWaypointIndex to 1
    disconnect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
    _nextPhaseStartWaypointIndex.setRawValue(int(1));
    connect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
476

477 478
    if(!calcNextPhase())
        return false;
479

480

481 482

    emit visualItemsChanged();
483
    emit missionItemsChanged();
484

485 486 487

    _localPlanDataValid = true;
    return true;
488 489
}

490
bool WimaController::calcNextPhase()
491
{
492 493 494 495 496 497 498 499 500 501 502 503
    if (_missionItems.count() < 1 || _lastMissionPhaseReached)
        return false;

    _currentMissionItems.clear();
    _currentWaypointPath.clear();
    emit currentMissionItemsChanged();
    emit currentWaypointPathChanged();

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

504

505 506 507
    int maxWaypointsPerPhaseInt = _maxWaypointsPerPhase.rawValue().toInt();

    // determine end waypoint index
508 509 510
    _endWaypointIndex = std::min(_startWaypointIndex + maxWaypointsPerPhaseInt - 1, _missionItems.count()-1);
    if (_endWaypointIndex == _missionItems.count() - 1)
        _lastMissionPhaseReached = true;
511

512
    // extract waypoints
513
    QList<QGeoCoordinate> geoCoordinateList; // list with potential waypoints (from _missionItems), for _currentMissionItems
514
    if (!extractCoordinateList(_missionItems, geoCoordinateList, _startWaypointIndex, _endWaypointIndex)) {
515 516
        qWarning("WimaController::calcNextPhase(): error on waypoint extraction.");
        return false;
517
    }
518 519

    // set start waypoint index for next phase
520 521 522 523 524 525
    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);
526
    }
527 528 529

    // calculate path from home to first waypoint
    QList<QGeoCoordinate> path;
530 531 532 533
    if (!_takeoffLandPostion.isValid()){
        qWarning("WimaController::calcNextPhase(): _takeoffLandPostion not valid.");
        return false;
    }
534
    if ( !calcShortestPath(_takeoffLandPostion, geoCoordinateList[0], path) ) {
535 536
        qWarning("WimaController::calcNextPhase(): Not able to calc path from home to first waypoint.");
        return false;
537 538 539 540 541 542 543
    }
    // 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();
544
    if ( !calcShortestPath(geoCoordinateList.last(), _takeoffLandPostion, path) ) {
545 546
        qWarning("WimaController::calcNextPhase(): Not able to calc path from home to first waypoint.");
        return false;
547 548 549 550
    }
    path.removeFirst(); // first coordinate already in geoCoordinateList
    geoCoordinateList.append(path);

551

552 553 554
    // create Mission Items
    _missionController->removeAll();
    QmlObjectListModel* missionControllerVisuals = _missionController->visualItems();
555 556 557 558

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

    for (auto coordinate : geoCoordinateList) {
565
        _missionController->insertSimpleMissionItem(coordinate, missionControllerVisuals->count());
566 567
    }

568 569 570 571 572
    // set takeoff position for first mission item (bug)
    SimpleMissionItem *takeoffItem = missionControllerVisuals->value<SimpleMissionItem*>(1);
    if (takeoffItem == nullptr) {
        qWarning("WimaController::calcNextPhase(): nullptr");
        return false;
573
    }
574
    takeoffItem->setCoordinate(_takeoffLandPostion);
575

576 577 578 579 580 581 582 583 584 585 586
    // 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());

587 588 589 590

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

596
    // copy to _currentMissionItems
597 598 599
    for ( int i = 1; i < missionControllerVisuals->count(); i++) {
        SimpleMissionItem *visualItem     = missionControllerVisuals->value<SimpleMissionItem*>(i);
        if (visualItem == nullptr) {
600
            qWarning("WimaController::calcNextPhase(): Nullptr at SimpleMissionItem!");
601
            _currentMissionItems.clear();
602
            return false;
603
        }
604

605
        SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
606 607
        _currentMissionItems.append(visualItemCopy);
    }
608

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

614
    updateCurrentPath();
615
    emit currentMissionItemsChanged();
616 617

    return true;
618
}
619

620 621 622
void WimaController::updateWaypointPath()
{
    _waypointPath.clear();
623
    extractCoordinateList(_missionItems, _waypointPath, 0, _missionItems.count()-1);
624

625 626 627 628 629
    emit waypointPathChanged();
}
void WimaController::updateCurrentPath()
{
    _currentWaypointPath.clear();
630
    extractCoordinateList(_currentMissionItems, _currentWaypointPath, 0, _currentMissionItems.count()-1);
631

632 633
    emit currentWaypointPathChanged();
}
634

635 636 637
void WimaController::updateNextWaypoint()
{
    if (_endWaypointIndex < _missionItems.count()-2) {
638 639 640
        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);
641 642 643
    }
}

644 645
void WimaController::recalcCurrentPhase()
{
646
    _lastMissionPhaseReached = false;
647 648 649 650
    disconnect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
    _nextPhaseStartWaypointIndex.setRawValue(_startWaypointIndex + 1);    
    connect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
    calcNextPhase();
651 652 653 654 655 656 657 658 659
}

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

    return true;
660 661
}

662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703
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());
    }
}

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

704 705