WimaController.cc 19.4 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 26 27 28 29 30 31 32 33 34 35
    : 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])
    , _startWaypointIndex       (settingsGroup, _metaDataMap[startWaypointIndexName])
    , _showAllMissionItems      (settingsGroup, _metaDataMap[showAllMissionItemsName])
    , _showCurrentMissionItems  (settingsGroup, _metaDataMap[showCurrentMissionItemsName])
{
    _startWaypointIndex.setRawValue(int(1));
    _showAllMissionItems.setRawValue(true);
    _showCurrentMissionItems.setRawValue(true);
    connect(&_overlapWaypoints,     &Fact::rawValueChanged, this, &WimaController::updateNextWaypoint);
    connect(&_maxWaypointsPerPhase, &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
    connect(&_startWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
36 37
}

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

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

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

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

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

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

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

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

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

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

85 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 113 114
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()
{
    return &_startWaypointIndex;
}

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

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

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

140
        _container = container;
141
        connect(_container, &WimaDataContainer::dataValidChanged, this, &WimaController::containerDataValidChanged);
142 143 144 145 146

        emit dataContainerChanged();
    }
}

147 148 149 150 151
void WimaController::nextPhase()
{
    updateCurrentMissionItems();
}

152 153
void WimaController::previousPhase()
{
154
    if (_startWaypointIndex.rawValue().toInt() > 0) {
155

156 157 158 159
        _startWaypointIndex.setRawValue(  _startWaypointIndex.rawValue().toInt() - _maxWaypointsPerPhase.rawValue().toInt()
                                        + _overlapWaypoints.rawValue().toInt());

    }
160 161 162 163
}

void WimaController::resetPhase()
{
164
    _startWaypointIndex.setRawValue(int(1));
165 166 167 168
}

void WimaController::uploadToVehicle()
{
169 170
    _masterController->sendToVehicle();
}
171

172 173 174
void WimaController::removeFromVehicle()
{
    _masterController->removeAllFromVehicle();
175 176
}

177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196
void WimaController::startMission()
{

}

void WimaController::abortMission()
{

}

void WimaController::pauseMission()
{

}

void WimaController::resumeMission()
{

}

197
void WimaController::saveToCurrent()
198 199 200
{
}

201 202
void WimaController::saveToFile(const QString& filename)
{
203
    QString file = filename;
204 205
}

206
bool WimaController::loadFromCurrent()
207
{
208
    return true;
209 210 211 212
}

bool WimaController::loadFromFile(const QString &filename)
{
213
    QString file = filename;
214
    return true;
215 216 217
}


218

219
QJsonDocument WimaController::saveToJson(FileType fileType)
220
{
221 222 223 224
    if(fileType)
    {

    }
225
    return QJsonDocument();
226 227
}

228 229 230 231 232 233 234 235 236 237 238 239 240 241 242
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;
}

243
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList)
244 245 246 247
{
    return extractCoordinateList(missionItems, coordinateList, 0, missionItems.count()-1);
}

248
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QList<QGeoCoordinate> &coordinateList, int startIndex, int endIndex)
249 250 251 252 253 254 255 256 257 258 259 260
{
    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++) {
261
                SimpleMissionItem *mItem = missionItems.value<SimpleMissionItem *>(i);
262 263 264 265 266 267 268 269 270 271 272 273 274 275

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

    return true;
}

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

281
bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList, int startIndex, int endIndex)
282 283 284 285 286 287 288 289 290 291 292 293 294 295
{
    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;
}

296 297 298 299 300 301 302 303
/*!
 * \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
 */
void WimaController::containerDataValidChanged(bool valid)
304
{
305 306 307 308 309
    if ( valid ) {
        if (_container == nullptr) {
            qWarning("WimaController::containerDataValidChanged(): No container assigned!");
        }
        _localPlanDataValid = false;
310
        _visualItems.clear();
311
        _missionItems.clear();
312 313 314 315 316 317 318 319 320 321 322
        WimaPlanData planData = _container->pull();

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

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

            if (areaData->type() == WimaServiceAreaData::typeString) { // is it a service area?
323
                _serviceArea = *qobject_cast<const WimaServiceAreaData*>(areaData);
324
                areaCounter++;
325
                _visualItems.append(&_serviceArea);
326 327 328 329

                continue;
            }

330 331
            if (areaData->type() == WimaMeasurementAreaData::typeString) { // is it a measurement area?
                _measurementArea =  *qobject_cast<const WimaMeasurementAreaData*>(areaData);
332
                areaCounter++;
333
                _visualItems.append(&_measurementArea);
334 335 336 337

                continue;
            }

338 339
            if (areaData->type() == WimaCorridorData::typeString) { // is it a corridor?
                _corridor =  *qobject_cast<const WimaCorridorData*>(areaData);
340
                areaCounter++;
341
                //_visualItems.append(&_corridor); // not needed
342 343 344 345

                continue;
            }

346 347
            if (areaData->type() == WimaJoinedAreaData::typeString) { // is it a corridor?
                _joinedArea =  *qobject_cast<const WimaJoinedAreaData*>(areaData);
348
                areaCounter++;
349
                _visualItems.append(&_joinedArea);
350 351

                continue;
352
            }
353 354 355 356

            if (areaCounter >= numAreas)
                break;
        }
357 358
        QList<const MissionItem*> tempMissionItems = planData.missionItems();

359
        // create mission items
360
        _missionController->removeAll();
361
        QmlObjectListModel* missionControllerVisualItems = _missionController->visualItems();
362 363 364 365 366


        // find takeoff command
        int begin = -1;
        for (int i = 0; i < tempMissionItems.size(); i++) {
367
            const MissionItem *missionItem = tempMissionItems[i];
368 369 370
            if (    missionItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF
                 || missionItem->command() == MAV_CMD_NAV_TAKEOFF) {

371
                _missionController->insertSimpleMissionItem(*missionItem, missionControllerVisualItems->count());
372 373 374 375 376 377 378 379

                QGeoCoordinate coordinate = missionItem->coordinate();
                _takeoffLandPostion.setAltitude(coordinate.altitude());
                _takeoffLandPostion.setLatitude(coordinate.latitude());
                _takeoffLandPostion.setLongitude(coordinate.longitude());

                begin = i + 1;
                break;
380
            }
381 382 383 384 385 386 387 388 389 390 391 392
        }

        // check if takeoff command found
        if (begin < 0) {
            qWarning("WimaController::containerDataValidChanged(): No takeoff found.");
            return;
        }

        // copy mission items and create SimpleMissionItem by using _missionController
        for ( int i = begin; i < tempMissionItems.size(); i++) {
            const MissionItem *missionItem = tempMissionItems[i];
            _missionController->insertSimpleMissionItem(*missionItem, missionControllerVisualItems->count());
393 394 395

            if (    missionItem->command() == MAV_CMD_NAV_VTOL_LAND
                 || missionItem->command() == MAV_CMD_NAV_LAND)
396
                 break;
397
        }
398 399 400 401 402 403 404 405 406 407 408

        for ( int i = 1; i < missionControllerVisualItems->count(); i++) {
            SimpleMissionItem *visualItem     = qobject_cast<SimpleMissionItem *>((*missionControllerVisualItems)[i]);
            if (visualItem == nullptr) {
                qWarning("WimaController::containerDataValidChanged(): Nullptr at SimpleMissionItem!");
                return;
            }
            SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
            _missionItems.append(visualItemCopy);
        }

409 410
        if (areaCounter == numAreas)
            _localPlanDataValid = true;
411

412
        updateWaypointPath();
413
        _startWaypointIndex.setRawValue(int(1));
414
        updateCurrentMissionItems();
415

416 417
    } else {
        _localPlanDataValid = false;
418 419
        _visualItems.clear();
        _missionItems.clear();
420
    }
421 422

    emit visualItemsChanged();
423
    emit missionItemsChanged();
424 425 426 427 428

#ifdef QT_DEBUG
    //qWarning("Mission Items count: ");
    //qWarning() << _missionItems.count();
#endif
429 430
}

431
void WimaController::updateCurrentMissionItems()
432
{
433 434 435
    int startWaypointIndexInt = _startWaypointIndex.rawValue().toInt()-1;
    // check if data was fetched and mission end is not reached yet
    if (_missionItems.count() < 1 || !_localPlanDataValid || startWaypointIndexInt >= _missionItems.count()-2)
436 437
        return;

438 439 440 441
    int maxWaypointsPerPhaseInt = _maxWaypointsPerPhase.rawValue().toInt();

    // determine end waypoint index
    _endWaypointIndex = std::min(startWaypointIndexInt + maxWaypointsPerPhaseInt - 1, _missionItems.count()-2); // -2 -> last item is land item
442

443
    // extract waypoints
444
    QList<QGeoCoordinate> geoCoordinateList; // list with potential waypoints (from _missionItems), for _currentMissionItems
445
    if (!extractCoordinateList(_missionItems, geoCoordinateList, startWaypointIndexInt, _endWaypointIndex)) {
446
        qWarning("WimaController::updateCurrentMissionItems(): error on waypoint extraction.");
447
        _currentMissionItems.clear();
448
        return;
449
    }
450 451 452 453 454 455 456 457 458 459 460 461 462 463

    // set start waypoint index for next phase
    if (_endWaypointIndex < _missionItems.count()-2) {
        _startWaypointIndexList.append(_startWaypointIndex.rawValue().toInt());

        disconnect(&_startWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
        _startWaypointIndex.setRawValue(std::max(_endWaypointIndex + 2 - _overlapWaypoints.rawValue().toInt(), 1));
        connect(&_startWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
    }
    else {
        disconnect(&_startWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
        _startWaypointIndex.setRawValue(_missionItems.count()-1); // marks that end of mission is reached
        connect(&_startWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
    }
464 465 466

    // calculate path from home to first waypoint
    QList<QGeoCoordinate> path;
467
    if ( !calcShortestPath(_takeoffLandPostion, geoCoordinateList[0], path) ) {
468
        qWarning("WimaController::updateCurrentMissionItems(): Not able to calc path from home to first waypoint.");
469
        _currentMissionItems.clear();
470 471 472 473 474 475 476 477
        return;
    }
    // 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();
478
    if ( !calcShortestPath(geoCoordinateList.last(), _takeoffLandPostion, path) ) {
479
        qWarning("WimaController::updateCurrentMissionItems(): Not able to calc path from home to first waypoint.");
480
        _currentMissionItems.clear();
481 482 483 484 485
        return;
    }
    path.removeFirst(); // first coordinate already in geoCoordinateList
    geoCoordinateList.append(path);

486

487 488 489
    // create Mission Items
    _missionController->removeAll();
    QmlObjectListModel* missionControllerVisuals = _missionController->visualItems();
490 491 492 493 494 495 496 497 498 499 500

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

    for (auto coordinate : geoCoordinateList) {
501
        _missionController->insertSimpleMissionItem(coordinate, missionControllerVisuals->count());
502 503 504 505 506 507 508 509 510 511 512
    }

    // set homeposition for take off item (somehow not working with insertSimpleMissionItem)
    SimpleMissionItem* takeoff = missionControllerVisuals->value<SimpleMissionItem *>(1);
    if (takeoff == nullptr) {
        qWarning("WimaController::updateCurrentMissionItems(): nullptr");
        _currentMissionItems.clear();
        return;
    }
    takeoff->setCoordinate(_takeoffLandPostion);

513 514 515 516 517

    // set land command for last mission item
    SimpleMissionItem *landItem = missionControllerVisuals->value<SimpleMissionItem*>(missionControllerVisuals->count()-1);
    if (landItem == nullptr) {
        qWarning("WimaController::updateCurrentMissionItems(): nullptr");
518
        _currentMissionItems.clear();
519 520 521 522 523 524 525
        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);
526 527
    } else {
        _currentMissionItems.clear();
528
        return;
529
    }
530

531
    // copy to _currentMissionItems
532
    _currentMissionItems.clear();
533 534 535
    for ( int i = 1; i < missionControllerVisuals->count(); i++) {
        SimpleMissionItem *visualItem     = missionControllerVisuals->value<SimpleMissionItem*>(i);
        if (visualItem == nullptr) {
536 537
            qWarning("WimaController::updateCurrentMissionItems(): Nullptr at SimpleMissionItem!");            
            _currentMissionItems.clear();
538 539
            return;
        }
540

541 542 543
        SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
        _currentMissionItems.append(visualItemCopy);
    }
544

545
    updateCurrentPath();
546
    emit currentMissionItemsChanged();
547
}
548

549 550 551
void WimaController::updateWaypointPath()
{
    _waypointPath.clear();
552
    extractCoordinateList(_missionItems, _waypointPath, 0, _missionItems.count()-1);
553

554 555 556 557 558
    emit waypointPathChanged();
}
void WimaController::updateCurrentPath()
{
    _currentWaypointPath.clear();
559
    extractCoordinateList(_currentMissionItems, _currentWaypointPath, 0, _currentMissionItems.count()-1);
560

561 562
    emit currentWaypointPathChanged();
}
563

564 565 566 567 568 569 570 571 572
void WimaController::updateNextWaypoint()
{
    if (_endWaypointIndex < _missionItems.count()-2) {
        disconnect(&_startWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
        _startWaypointIndex.setRawValue(_endWaypointIndex + 2 - _overlapWaypoints.rawValue().toInt());
        connect(&_startWaypointIndex,   &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
    }
}

573 574