WimaController.cc 20.3 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
WimaController::WimaController(QObject *parent)
15 16 17 18 19 20 21 22 23 24 25
    : 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])
26
    , _nextPhaseStartWaypointIndex       (settingsGroup, _metaDataMap[startWaypointIndexName])
27 28
    , _showAllMissionItems      (settingsGroup, _metaDataMap[showAllMissionItemsName])
    , _showCurrentMissionItems  (settingsGroup, _metaDataMap[showCurrentMissionItemsName])
29
    , _startWaypointIndex       (0)
30
    , _lastMissionPhaseReached  (false)
31 32
    , _uploadOverrideRequired   (false)

33
{
34
    _nextPhaseStartWaypointIndex.setRawValue(int(1));
35 36 37
    _showAllMissionItems.setRawValue(true);
    _showCurrentMissionItems.setRawValue(true);
    connect(&_overlapWaypoints,     &Fact::rawValueChanged, this, &WimaController::updateNextWaypoint);
38
    connect(&_maxWaypointsPerPhase, &Fact::rawValueChanged, this, &WimaController::recalcCurrentPhase);
39
    connect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
40 41
}

42
QmlObjectListModel* WimaController::visualItems()
43
{
44
    return &_visualItems;
45 46
}

Valentin Platzgummer's avatar
Valentin Platzgummer committed
47 48 49 50
QStringList WimaController::loadNameFilters() const
{
    QStringList filters;

51
    filters << tr("Supported types (*.%1 *.%2)").arg(wimaFileExtension).arg(AppSettings::planFileExtension) <<
Valentin Platzgummer's avatar
Valentin Platzgummer committed
52 53
               tr("All Files (*.*)");
    return filters;
54 55 56 57 58
}

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

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

64
WimaDataContainer *WimaController::dataContainer()
65
{
66
    return _container;
67 68
}

69 70 71 72 73
QmlObjectListModel *WimaController::missionItems()
{
    return &_missionItems;
}

74 75 76 77 78
QmlObjectListModel *WimaController::currentMissionItems()
{
    return &_currentMissionItems;
}

79 80 81 82 83
QVariantList WimaController::waypointPath()
{
    return  _waypointPath;
}

84 85 86 87 88
QVariantList WimaController::currentWaypointPath()
{
    return _currentWaypointPath;
}

89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113
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;
}

114 115 116 117 118
bool WimaController::uploadOverrideRequired() const
{
    return _uploadOverrideRequired;
}

119 120
Fact *WimaController::startWaypointIndex()
{
121
    return &_nextPhaseStartWaypointIndex;
122 123
}

124 125 126 127 128 129 130 131 132 133 134 135
void WimaController::setMasterController(PlanMasterController *masterC)
{
    _masterController = masterC;
    emit masterControllerChanged();
}

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

136 137 138 139 140 141
/*!
 * \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
 */
142 143
void WimaController::setDataContainer(WimaDataContainer *container)
{
144 145
    if (container != nullptr) {
        if (_container != nullptr) {
146
           disconnect(_container, &WimaDataContainer::newDataAvailable, this, &WimaController::fetchContainerData);
147 148
        }

149
        _container = container;
150
        connect(_container, &WimaDataContainer::newDataAvailable, this, &WimaController::fetchContainerData);
151 152 153 154 155

        emit dataContainerChanged();
    }
}

156 157 158 159 160 161 162 163 164
void WimaController::setUploadOverrideRequired(bool overrideRequired)
{
    if (_uploadOverrideRequired != overrideRequired) {
        _uploadOverrideRequired = overrideRequired;

        emit uploadOverrideRequiredChanged();
    }
}

165 166
void WimaController::nextPhase()
{
167
    calcNextPhase();
168 169
}

170 171
void WimaController::previousPhase()
{
172 173
    if (_nextPhaseStartWaypointIndex.rawValue().toInt() > 0) {
        _lastMissionPhaseReached = false;
174 175 176
        _nextPhaseStartWaypointIndex.setRawValue(std::max(_startWaypointIndex
                                                          - _maxWaypointsPerPhase.rawValue().toInt()
                                                          + _overlapWaypoints.rawValue().toInt(), 1));
177
    }
178 179 180 181
}

void WimaController::resetPhase()
{
182 183
    _lastMissionPhaseReached = false;
    _nextPhaseStartWaypointIndex.setRawValue(int(1));
184 185
}

186
bool WimaController::uploadToVehicle()
187
{
188 189
    if (   !_serviceArea.containsCoordinate(_masterController->managerVehicle()->coordinate())
        && _currentMissionItems.count() > 0) {
190 191 192 193 194 195 196 197 198 199
        setUploadOverrideRequired(true);
        return false;
    }

    return forceUploadToVehicle();
}

bool WimaController::forceUploadToVehicle()
{
    setUploadOverrideRequired(false);
200
    if (_currentMissionItems.count() < 1)
201
        return false;
202 203 204 205 206 207 208

    _missionController->removeAll();
    // set homeposition of settingsItem
    QmlObjectListModel* visuals = _missionController->visualItems();
    MissionSettingsItem* settingsItem = visuals->value<MissionSettingsItem *>(0);
    if (settingsItem == nullptr) {
        qWarning("WimaController::updateCurrentMissionItems(): nullptr");
209
        return false;
210 211 212 213 214 215 216 217 218
    }
    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());
    }

219
    _masterController->sendToVehicle();
220 221

    return true;
222
}
223

224 225 226
void WimaController::removeFromVehicle()
{
    _masterController->removeAllFromVehicle();
227 228
}

229
void WimaController::saveToCurrent()
230
{
231

232 233
}

234 235
void WimaController::saveToFile(const QString& filename)
{
236
    QString file = filename;
237 238
}

239
bool WimaController::loadFromCurrent()
240
{
241
    return true;
242 243 244 245
}

bool WimaController::loadFromFile(const QString &filename)
{
246
    QString file = filename;
247
    return true;
248 249 250
}


251

252
QJsonDocument WimaController::saveToJson(FileType fileType)
253
{
254 255 256 257
    if(fileType)
    {

    }
258
    return QJsonDocument();
259 260
}

261 262 263 264 265 266 267 268 269 270 271 272 273 274 275
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;
}

276
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList)
277 278 279 280
{
    return extractCoordinateList(missionItems, coordinateList, 0, missionItems.count()-1);
}

281
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList, int startIndex, int endIndex)
282 283 284 285 286 287 288 289 290 291 292 293
{
    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++) {
294
                SimpleMissionItem *mItem = missionItems.value<SimpleMissionItem *>(i);
295 296 297 298 299 300 301 302 303 304 305 306 307 308

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

    return true;
}

309
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList)
310 311 312 313
{
    return extractCoordinateList(missionItems, coordinateList, 0 , missionItems.count()-1);
}

314
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList, int startIndex, int endIndex)
315 316 317 318 319 320 321 322 323 324 325 326 327 328
{
    QList<QGeoCoordinate> geoCoordintateList;

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

    if (!retValue)
        return false;

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

    return true;
}

329 330 331 332 333 334 335
/*!
 * \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
 */
336
bool WimaController::fetchContainerData()
337
{
338
    // fetch only if valid, return true on sucess
339

340 341 342 343 344 345
    // reset visual items
    _visualItems.clear();
    _missionItems.clear();
    _currentMissionItems.clear();
    _waypointPath.clear();
    _currentWaypointPath.clear();
346

347 348 349 350
    emit visualItemsChanged();
    emit missionItemsChanged();
    emit currentMissionItemsChanged();
    emit currentWaypointPathChanged();
351

352 353
    _localPlanDataValid = false;
    _lastMissionPhaseReached = false;
354

355 356 357 358
    if (_container == nullptr) {
        qWarning("WimaController::fetchContainerData(): No container assigned!");
        return false;
    }
359

360
    WimaPlanData planData = _container->pull();
361

362 363
    // extract list with WimaAreas
    QList<const WimaAreaData*> areaList = planData.areaList();
364

365 366 367 368
    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];
369

370 371 372 373
        if (areaData->type() == WimaServiceAreaData::typeString) { // is it a service area?
            _serviceArea = *qobject_cast<const WimaServiceAreaData*>(areaData);
            areaCounter++;
            _visualItems.append(&_serviceArea);
374

375 376
            continue;
        }
377

378 379 380 381
        if (areaData->type() == WimaMeasurementAreaData::typeString) { // is it a measurement area?
            _measurementArea =  *qobject_cast<const WimaMeasurementAreaData*>(areaData);
            areaCounter++;
            _visualItems.append(&_measurementArea);
382

383
            continue;
384
        }
385

386 387 388 389
        if (areaData->type() == WimaCorridorData::typeString) { // is it a corridor?
            _corridor =  *qobject_cast<const WimaCorridorData*>(areaData);
            areaCounter++;
            //_visualItems.append(&_corridor); // not needed
390

391 392
            continue;
        }
393

394 395 396 397
        if (areaData->type() == WimaJoinedAreaData::typeString) { // is it a corridor?
            _joinedArea =  *qobject_cast<const WimaJoinedAreaData*>(areaData);
            areaCounter++;
            _visualItems.append(&_joinedArea);
398

399 400
            continue;
        }
401

402 403 404
        if (areaCounter >= numAreas)
            break;
    }
405

406 407 408 409
    // extract mission items
    QList<const MissionItem*> tempMissionItems = planData.missionItems();
    if (tempMissionItems.size() < 1)
        return false;
410

411 412 413 414 415 416 417 418 419 420 421 422 423 424 425
    // 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;
426
        }
427 428 429 430 431
        SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
        _missionItems.append(visualItemCopy);
    }
    if (areaCounter != numAreas)
        return false;
432

433 434
    if (!setTakeoffLandPosition())
        return false;
435

436
    updateWaypointPath();
437

438 439 440 441
    // set _nextPhaseStartWaypointIndex to 1
    disconnect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
    _nextPhaseStartWaypointIndex.setRawValue(int(1));
    connect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
442

443 444
    if(!calcNextPhase())
        return false;
445

446

447 448

    emit visualItemsChanged();
449
    emit missionItemsChanged();
450

451 452 453

    _localPlanDataValid = true;
    return true;
454 455
}

456
bool WimaController::calcNextPhase()
457
{
458 459 460 461 462 463 464 465 466 467 468 469
    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;

470

471 472 473
    int maxWaypointsPerPhaseInt = _maxWaypointsPerPhase.rawValue().toInt();

    // determine end waypoint index
474 475 476
    _endWaypointIndex = std::min(_startWaypointIndex + maxWaypointsPerPhaseInt - 1, _missionItems.count()-1);
    if (_endWaypointIndex == _missionItems.count() - 1)
        _lastMissionPhaseReached = true;
477

478
    // extract waypoints
479
    QList<QGeoCoordinate> geoCoordinateList; // list with potential waypoints (from _missionItems), for _currentMissionItems
480
    if (!extractCoordinateList(_missionItems, geoCoordinateList, _startWaypointIndex, _endWaypointIndex)) {
481 482
        qWarning("WimaController::calcNextPhase(): error on waypoint extraction.");
        return false;
483
    }
484 485

    // set start waypoint index for next phase
486 487 488 489 490 491
    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);
492
    }
493 494 495

    // calculate path from home to first waypoint
    QList<QGeoCoordinate> path;
496 497 498 499
    if (!_takeoffLandPostion.isValid()){
        qWarning("WimaController::calcNextPhase(): _takeoffLandPostion not valid.");
        return false;
    }
500
    if ( !calcShortestPath(_takeoffLandPostion, geoCoordinateList[0], path) ) {
501 502
        qWarning("WimaController::calcNextPhase(): Not able to calc path from home to first waypoint.");
        return false;
503 504 505 506 507 508 509
    }
    // 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();
510
    if ( !calcShortestPath(geoCoordinateList.last(), _takeoffLandPostion, path) ) {
511 512
        qWarning("WimaController::calcNextPhase(): Not able to calc path from home to first waypoint.");
        return false;
513 514 515 516
    }
    path.removeFirst(); // first coordinate already in geoCoordinateList
    geoCoordinateList.append(path);

517

518 519 520
    // create Mission Items
    _missionController->removeAll();
    QmlObjectListModel* missionControllerVisuals = _missionController->visualItems();
521 522 523 524

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

    for (auto coordinate : geoCoordinateList) {
531
        _missionController->insertSimpleMissionItem(coordinate, missionControllerVisuals->count());
532 533
    }

534 535 536 537 538
    // set takeoff position for first mission item (bug)
    SimpleMissionItem *takeoffItem = missionControllerVisuals->value<SimpleMissionItem*>(1);
    if (takeoffItem == nullptr) {
        qWarning("WimaController::calcNextPhase(): nullptr");
        return false;
539
    }
540
    takeoffItem->setCoordinate(_takeoffLandPostion);
541

542 543 544 545

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

551
    // copy to _currentMissionItems
552 553 554
    for ( int i = 1; i < missionControllerVisuals->count(); i++) {
        SimpleMissionItem *visualItem     = missionControllerVisuals->value<SimpleMissionItem*>(i);
        if (visualItem == nullptr) {
555
            qWarning("WimaController::calcNextPhase(): Nullptr at SimpleMissionItem!");
556
            _currentMissionItems.clear();
557
            return false;
558
        }
559

560
        SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
561 562
        _currentMissionItems.append(visualItemCopy);
    }
563

564 565
    _missionController->removeAll(); // remove items from _missionController, will be added on upload

566
    updateCurrentPath();
567
    emit currentMissionItemsChanged();
568 569

    return true;
570
}
571

572 573 574
void WimaController::updateWaypointPath()
{
    _waypointPath.clear();
575
    extractCoordinateList(_missionItems, _waypointPath, 0, _missionItems.count()-1);
576

577 578 579 580 581
    emit waypointPathChanged();
}
void WimaController::updateCurrentPath()
{
    _currentWaypointPath.clear();
582
    extractCoordinateList(_currentMissionItems, _currentWaypointPath, 0, _currentMissionItems.count()-1);
583

584 585
    emit currentWaypointPathChanged();
}
586

587 588 589
void WimaController::updateNextWaypoint()
{
    if (_endWaypointIndex < _missionItems.count()-2) {
590 591 592
        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);
593 594 595
    }
}

596 597
void WimaController::recalcCurrentPhase()
{
598
    _lastMissionPhaseReached = false;
599 600 601 602
    disconnect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
    _nextPhaseStartWaypointIndex.setRawValue(_startWaypointIndex + 1);    
    connect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
    calcNextPhase();
603 604 605 606 607 608 609 610 611
}

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

    return true;
612 613
}

614 615