WimaController.cc 20.1 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
    , _lastMissionPhaseReached  (false)
30
{
31
    _nextPhaseStartWaypointIndex.setRawValue(int(1));
32 33 34
    _showAllMissionItems.setRawValue(true);
    _showCurrentMissionItems.setRawValue(true);
    connect(&_overlapWaypoints,     &Fact::rawValueChanged, this, &WimaController::updateNextWaypoint);
35
    connect(&_maxWaypointsPerPhase, &Fact::rawValueChanged, this, &WimaController::recalcCurrentPhase);
36
    connect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
37 38
}

39
QmlObjectListModel* WimaController::visualItems()
40
{
41
    return &_visualItems;
42 43
}

Valentin Platzgummer's avatar
Valentin Platzgummer committed
44 45 46 47
QStringList WimaController::loadNameFilters() const
{
    QStringList filters;

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

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

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

61
WimaDataContainer *WimaController::dataContainer()
62
{
63
    return _container;
64 65
}

66 67 68 69 70
QmlObjectListModel *WimaController::missionItems()
{
    return &_missionItems;
}

71 72 73 74 75
QmlObjectListModel *WimaController::currentMissionItems()
{
    return &_currentMissionItems;
}

76 77 78 79 80
QVariantList WimaController::waypointPath()
{
    return  _waypointPath;
}

81 82 83 84 85
QVariantList WimaController::currentWaypointPath()
{
    return _currentWaypointPath;
}

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

Fact *WimaController::startWaypointIndex()
{
113
    return &_nextPhaseStartWaypointIndex;
114 115
}

116 117 118 119 120 121 122 123 124 125 126 127
void WimaController::setMasterController(PlanMasterController *masterC)
{
    _masterController = masterC;
    emit masterControllerChanged();
}

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

128 129 130 131 132 133
/*!
 * \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
 */
134 135
void WimaController::setDataContainer(WimaDataContainer *container)
{
136 137
    if (container != nullptr) {
        if (_container != nullptr) {
138
           disconnect(_container, &WimaDataContainer::newDataAvailable, this, &WimaController::fetchContainerData);
139 140
        }

141
        _container = container;
142
        connect(_container, &WimaDataContainer::newDataAvailable, this, &WimaController::fetchContainerData);
143 144 145 146 147

        emit dataContainerChanged();
    }
}

148 149
void WimaController::nextPhase()
{
150
    calcNextPhase();
151 152
}

153 154
void WimaController::previousPhase()
{
155 156 157
    if (_nextPhaseStartWaypointIndex.rawValue().toInt() > 0) {
        _lastMissionPhaseReached = false;
        _nextPhaseStartWaypointIndex.setRawValue(   1 + std::max(_startWaypointIndex
158 159
                                                  - _maxWaypointsPerPhase.rawValue().toInt()
                                                  + _overlapWaypoints.rawValue().toInt(), 0));
160
    }
161 162 163 164
}

void WimaController::resetPhase()
{
165 166
    _lastMissionPhaseReached = false;
    _nextPhaseStartWaypointIndex.setRawValue(int(1));
167 168
}

169
bool WimaController::uploadToVehicle()
170
{
171
    if (_currentMissionItems.count() < 1)
172
        return false;
173 174 175 176 177 178 179

    _missionController->removeAll();
    // set homeposition of settingsItem
    QmlObjectListModel* visuals = _missionController->visualItems();
    MissionSettingsItem* settingsItem = visuals->value<MissionSettingsItem *>(0);
    if (settingsItem == nullptr) {
        qWarning("WimaController::updateCurrentMissionItems(): nullptr");
180
        return false;
181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206
    }
    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());
    }

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

//    // check vehicle type, before setting land command
//    Vehicle* controllerVehicle = _masterController->controllerVehicle();
//    MAV_CMD landCmd = controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_LAND;
//    if (controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(landCmd)) {
//        landItem->setCommand(landCmd);
//    } else {
//        _missionController->removeAll();
//        return;
//    }
207
    _masterController->sendToVehicle();
208 209

    return true;
210
}
211

212 213 214
void WimaController::removeFromVehicle()
{
    _masterController->removeAllFromVehicle();
215 216
}

217
void WimaController::saveToCurrent()
218
{
219

220 221
}

222 223
void WimaController::saveToFile(const QString& filename)
{
224
    QString file = filename;
225 226
}

227
bool WimaController::loadFromCurrent()
228
{
229
    return true;
230 231 232 233
}

bool WimaController::loadFromFile(const QString &filename)
{
234
    QString file = filename;
235
    return true;
236 237 238
}


239

240
QJsonDocument WimaController::saveToJson(FileType fileType)
241
{
242 243 244 245
    if(fileType)
    {

    }
246
    return QJsonDocument();
247 248
}

249 250 251 252 253 254 255 256 257 258 259 260 261 262 263
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;
}

264
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList)
265 266 267 268
{
    return extractCoordinateList(missionItems, coordinateList, 0, missionItems.count()-1);
}

269
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList, int startIndex, int endIndex)
270 271 272 273 274 275 276 277 278 279 280 281
{
    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++) {
282
                SimpleMissionItem *mItem = missionItems.value<SimpleMissionItem *>(i);
283 284 285 286 287 288 289 290 291 292 293 294 295 296

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

    return true;
}

297
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList)
298 299 300 301
{
    return extractCoordinateList(missionItems, coordinateList, 0 , missionItems.count()-1);
}

302
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList, int startIndex, int endIndex)
303 304 305 306 307 308 309 310 311 312 313 314 315 316
{
    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;
}

317 318 319 320 321 322 323
/*!
 * \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
 */
324
bool WimaController::fetchContainerData()
325
{
326
    // fetch only if valid, return true on sucess
327

328 329 330 331 332 333
    // reset visual items
    _visualItems.clear();
    _missionItems.clear();
    _currentMissionItems.clear();
    _waypointPath.clear();
    _currentWaypointPath.clear();
334

335 336 337 338
    emit visualItemsChanged();
    emit missionItemsChanged();
    emit currentMissionItemsChanged();
    emit currentWaypointPathChanged();
339

340 341
    _localPlanDataValid = false;
    _lastMissionPhaseReached = false;
342

343 344 345 346
    if (_container == nullptr) {
        qWarning("WimaController::fetchContainerData(): No container assigned!");
        return false;
    }
347

348
    WimaPlanData planData = _container->pull();
349

350 351
    // extract list with WimaAreas
    QList<const WimaAreaData*> areaList = planData.areaList();
352

353 354 355 356
    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];
357

358 359 360 361
        if (areaData->type() == WimaServiceAreaData::typeString) { // is it a service area?
            _serviceArea = *qobject_cast<const WimaServiceAreaData*>(areaData);
            areaCounter++;
            _visualItems.append(&_serviceArea);
362

363 364
            continue;
        }
365

366 367 368 369
        if (areaData->type() == WimaMeasurementAreaData::typeString) { // is it a measurement area?
            _measurementArea =  *qobject_cast<const WimaMeasurementAreaData*>(areaData);
            areaCounter++;
            _visualItems.append(&_measurementArea);
370

371
            continue;
372
        }
373

374 375 376 377
        if (areaData->type() == WimaCorridorData::typeString) { // is it a corridor?
            _corridor =  *qobject_cast<const WimaCorridorData*>(areaData);
            areaCounter++;
            //_visualItems.append(&_corridor); // not needed
378

379 380
            continue;
        }
381

382 383 384 385
        if (areaData->type() == WimaJoinedAreaData::typeString) { // is it a corridor?
            _joinedArea =  *qobject_cast<const WimaJoinedAreaData*>(areaData);
            areaCounter++;
            _visualItems.append(&_joinedArea);
386

387 388
            continue;
        }
389

390 391 392
        if (areaCounter >= numAreas)
            break;
    }
393

394 395 396 397
    // extract mission items
    QList<const MissionItem*> tempMissionItems = planData.missionItems();
    if (tempMissionItems.size() < 1)
        return false;
398

399 400 401 402 403 404 405 406 407 408 409 410 411 412 413
    // 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;
414
        }
415 416 417 418 419
        SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
        _missionItems.append(visualItemCopy);
    }
    if (areaCounter != numAreas)
        return false;
420

421 422
    if (!setTakeoffLandPosition())
        return false;
423

424
    updateWaypointPath();
425

426 427 428 429
    // set _nextPhaseStartWaypointIndex to 1
    disconnect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
    _nextPhaseStartWaypointIndex.setRawValue(int(1));
    connect(&_nextPhaseStartWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::calcNextPhase);
430

431 432
    if(!calcNextPhase())
        return false;
433

434

435 436

    emit visualItemsChanged();
437
    emit missionItemsChanged();
438

439 440 441

    _localPlanDataValid = true;
    return true;
442 443
}

444
bool WimaController::calcNextPhase()
445
{
446 447 448 449 450 451 452 453 454 455 456 457
    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;

458

459 460 461
    int maxWaypointsPerPhaseInt = _maxWaypointsPerPhase.rawValue().toInt();

    // determine end waypoint index
462 463 464
    _endWaypointIndex = std::min(_startWaypointIndex + maxWaypointsPerPhaseInt - 1, _missionItems.count()-1);
    if (_endWaypointIndex == _missionItems.count() - 1)
        _lastMissionPhaseReached = true;
465

466
    // extract waypoints
467
    QList<QGeoCoordinate> geoCoordinateList; // list with potential waypoints (from _missionItems), for _currentMissionItems
468
    if (!extractCoordinateList(_missionItems, geoCoordinateList, _startWaypointIndex, _endWaypointIndex)) {
469 470
        qWarning("WimaController::calcNextPhase(): error on waypoint extraction.");
        return false;
471
    }
472 473

    // set start waypoint index for next phase
474 475 476 477 478 479
    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);
480
    }
481 482 483

    // calculate path from home to first waypoint
    QList<QGeoCoordinate> path;
484 485 486 487
    if (!_takeoffLandPostion.isValid()){
        qWarning("WimaController::calcNextPhase(): _takeoffLandPostion not valid.");
        return false;
    }
488
    if ( !calcShortestPath(_takeoffLandPostion, geoCoordinateList[0], path) ) {
489 490
        qWarning("WimaController::calcNextPhase(): Not able to calc path from home to first waypoint.");
        return false;
491 492 493 494 495 496 497
    }
    // 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();
498
    if ( !calcShortestPath(geoCoordinateList.last(), _takeoffLandPostion, path) ) {
499 500
        qWarning("WimaController::calcNextPhase(): Not able to calc path from home to first waypoint.");
        return false;
501 502 503 504
    }
    path.removeFirst(); // first coordinate already in geoCoordinateList
    geoCoordinateList.append(path);

505

506 507 508
    // create Mission Items
    _missionController->removeAll();
    QmlObjectListModel* missionControllerVisuals = _missionController->visualItems();
509 510 511 512

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

    for (auto coordinate : geoCoordinateList) {
519
        _missionController->insertSimpleMissionItem(coordinate, missionControllerVisuals->count());
520 521
    }

522 523 524 525 526
    // set takeoff position for first mission item (bug)
    SimpleMissionItem *takeoffItem = missionControllerVisuals->value<SimpleMissionItem*>(1);
    if (takeoffItem == nullptr) {
        qWarning("WimaController::calcNextPhase(): nullptr");
        return false;
527
    }
528
    takeoffItem->setCoordinate(_takeoffLandPostion);
529

530 531 532 533

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

539
    // copy to _currentMissionItems
540 541 542
    for ( int i = 1; i < missionControllerVisuals->count(); i++) {
        SimpleMissionItem *visualItem     = missionControllerVisuals->value<SimpleMissionItem*>(i);
        if (visualItem == nullptr) {
543
            qWarning("WimaController::calcNextPhase(): Nullptr at SimpleMissionItem!");
544
            _currentMissionItems.clear();
545
            return false;
546
        }
547

548
        SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
549 550
        _currentMissionItems.append(visualItemCopy);
    }
551

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

554
    updateCurrentPath();
555
    emit currentMissionItemsChanged();
556 557

    return true;
558
}
559

560 561 562
void WimaController::updateWaypointPath()
{
    _waypointPath.clear();
563
    extractCoordinateList(_missionItems, _waypointPath, 0, _missionItems.count()-1);
564

565 566 567 568 569
    emit waypointPathChanged();
}
void WimaController::updateCurrentPath()
{
    _currentWaypointPath.clear();
570
    extractCoordinateList(_currentMissionItems, _currentWaypointPath, 0, _currentMissionItems.count()-1);
571

572 573
    emit currentWaypointPathChanged();
}
574

575 576 577
void WimaController::updateNextWaypoint()
{
    if (_endWaypointIndex < _missionItems.count()-2) {
578 579 580
        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);
581 582 583
    }
}

584 585
void WimaController::recalcCurrentPhase()
{
586 587 588 589 590 591 592 593 594 595 596
    _lastMissionPhaseReached = false;
    _nextPhaseStartWaypointIndex.setRawValue(_startWaypointIndex + 1);
}

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

    return true;
597 598
}

599 600