AirMapManager.cc 23.7 KB
Newer Older
1 2
/****************************************************************************
 *
3
 *   (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9 10 11 12 13 14 15
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

#include "AirMapManager.h"
#include "Vehicle.h"
#include "QmlObjectListModel.h"
#include "JsonHelper.h"
#include "SettingsManager.h"
#include "AppSettings.h"
16
#include "QGCQGeoCoordinate.h"
17
#include "QGCApplication.h"
18 19 20 21 22 23

#include <QNetworkAccessManager>
#include <QUrlQuery>
#include <QJsonDocument>
#include <QJsonArray>
#include <QNetworkProxy>
24
#include <QSet>
25 26 27

QGC_LOGGING_CATEGORY(AirMapManagerLog, "AirMapManagerLog")

28 29 30

AirMapLogin::AirMapLogin(QNetworkAccessManager& networkManager, const QString& APIKey)
    : _networkManager(networkManager), _APIKey(APIKey)
31 32 33
{
}

34
void AirMapLogin::setCredentials(const QString& clientID, const QString& userName, const QString& password)
35
{
36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58
    logout();
    _clientID = clientID;
    _userName = userName;
    _password = password;
}

void AirMapLogin::login()
{
    if (isLoggedIn() || _isLoginInProgress) {
        return;
    }
    _isLoginInProgress = true;

    QUrlQuery postData;
    postData.addQueryItem(QStringLiteral("grant_type"), "password");
    postData.addQueryItem(QStringLiteral("client_id"), _clientID);
    postData.addQueryItem(QStringLiteral("connection"), "Username-Password-Authentication");
    postData.addQueryItem(QStringLiteral("username"), _userName);
    postData.addQueryItem(QStringLiteral("password"), _password);
    postData.addQueryItem(QStringLiteral("scope"), "openid offline_access");
    postData.addQueryItem(QStringLiteral("device"), "test");

    QUrl url(QStringLiteral("https://sso.airmap.io/oauth/ro"));
59

60
    _post(url, postData.toString(QUrl::FullyEncoded).toUtf8());
61 62
}

63
void AirMapLogin::_requestFinished(void)
64
{
65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97
    QNetworkReply* reply = qobject_cast<QNetworkReply*>(QObject::sender());
    _isLoginInProgress = false;

    QByteArray responseBytes = reply->readAll();
    QJsonParseError parseError;
    QJsonDocument responseJson = QJsonDocument::fromJson(responseBytes, &parseError);
    if (parseError.error != QJsonParseError::NoError) {
        QNetworkReply::NetworkError networkError = QNetworkReply::NetworkError::UnknownNetworkError;
        emit loginFailure(networkError, "", "");
        return;
    }
    QJsonObject rootObject = responseJson.object();

    // When an error occurs we still end up here
    if (reply->error() != QNetworkReply::NoError) {
        QJsonValue errorDescription = rootObject.value("error_description");
        QString serverError = "";
        if (errorDescription.isString()) {
            serverError = errorDescription.toString();
        }
        emit loginFailure(reply->error(), reply->errorString(), serverError);
        return;
    }

    _JWTToken = rootObject["id_token"].toString();

    if (_JWTToken == "") { // make sure we got a token
        QNetworkReply::NetworkError networkError = QNetworkReply::NetworkError::AuthenticationRequiredError;
        emit loginFailure(networkError, "", "");
        return;
    }

    emit loginSuccess();
98 99
}

100
void AirMapLogin::_requestError(QNetworkReply::NetworkError code)
101
{
102 103 104
    Q_UNUSED(code);
    // handled in _requestFinished()
}
105

106 107 108 109
void AirMapLogin::_post(QUrl url, const QByteArray& postData)
{
    QNetworkRequest request(url);
    request.setHeader(QNetworkRequest::ContentTypeHeader, "application/x-www-form-urlencoded");
110

111
    request.setRawHeader("X-API-Key", _APIKey.toUtf8());
112 113 114 115 116

    QNetworkProxy tProxy;
    tProxy.setType(QNetworkProxy::DefaultProxy);
    _networkManager.setProxy(tProxy);

117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165
    QNetworkReply* networkReply = _networkManager.post(request, postData);
    if (!networkReply) {
        QNetworkReply::NetworkError networkError = QNetworkReply::NetworkError::UnknownNetworkError;
        emit loginFailure(networkError, "", "");
        return;
    }

    connect(networkReply, &QNetworkReply::finished,                                                                 this, &AirMapLogin::_requestFinished);
    connect(networkReply, static_cast<void (QNetworkReply::*)(QNetworkReply::NetworkError)>(&QNetworkReply::error), this, &AirMapLogin::_requestError);
}


AirMapNetworking::AirMapNetworking(SharedData& networkingData)
    : _networkingData(networkingData)
{
}

void AirMapNetworking::post(QUrl url, const QByteArray& postData, bool isJsonData, bool requiresLogin)
{
    QNetworkRequest request(url);
    if (isJsonData) {
        request.setHeader(QNetworkRequest::ContentTypeHeader, "application/json; charset=utf-8");
    } else {
        request.setHeader(QNetworkRequest::ContentTypeHeader, "application/x-www-form-urlencoded");
    }

    request.setRawHeader("X-API-Key", _networkingData.airmapAPIKey.toUtf8());

    if (requiresLogin) {
        if (_networkingData.login.isLoggedIn()) {
            request.setRawHeader("Authorization", (QString("Bearer ")+_networkingData.login.JWTToken()).toUtf8());
        } else {
            connect(&_networkingData.login, &AirMapLogin::loginSuccess, this, &AirMapNetworking::_loginSuccess);
            connect(&_networkingData.login, &AirMapLogin::loginFailure, this, &AirMapNetworking::_loginFailure);
            _pendingRequest.type = RequestType::POST;
            _pendingRequest.url = url;
            _pendingRequest.postData = postData;
            _pendingRequest.isJsonData = isJsonData;
            _pendingRequest.requiresLogin = requiresLogin;
            _networkingData.login.login();
            return;
        }
    }

    QNetworkProxy tProxy;
    tProxy.setType(QNetworkProxy::DefaultProxy);
    _networkingData.networkManager.setProxy(tProxy);

    QNetworkReply* networkReply = _networkingData.networkManager.post(request, postData);
166
    if (!networkReply) {
167 168
        QNetworkReply::NetworkError networkError = QNetworkReply::NetworkError::UnknownNetworkError;
        emit error(networkError, "", "");
169 170 171
        return;
    }

172
    connect(networkReply, &QNetworkReply::finished, this, &AirMapNetworking::_requestFinished);
173 174
}

175 176 177 178 179 180 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 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228
void AirMapNetworking::_loginSuccess()
{
    disconnect(&_networkingData.login, &AirMapLogin::loginSuccess, this, &AirMapNetworking::_loginSuccess);
    disconnect(&_networkingData.login, &AirMapLogin::loginFailure, this, &AirMapNetworking::_loginFailure);

    if (_pendingRequest.type == RequestType::GET) {
        get(_pendingRequest.url, _pendingRequest.requiresLogin);
    } else if (_pendingRequest.type == RequestType::POST) {
        post(_pendingRequest.url, _pendingRequest.postData, _pendingRequest.isJsonData, _pendingRequest.requiresLogin);
    }
    _pendingRequest.type = RequestType::None;
}
void AirMapNetworking::_loginFailure(QNetworkReply::NetworkError networkError, const QString& errorString, const QString& serverErrorMessage)
{
    disconnect(&_networkingData.login, &AirMapLogin::loginSuccess, this, &AirMapNetworking::_loginSuccess);
    disconnect(&_networkingData.login, &AirMapLogin::loginFailure, this, &AirMapNetworking::_loginFailure);
    emit error(networkError, errorString, serverErrorMessage);
}

void AirMapNetworking::get(QUrl url, bool requiresLogin)
{
    QNetworkRequest request(url);

    request.setRawHeader("X-API-Key", _networkingData.airmapAPIKey.toUtf8());

    if (requiresLogin) {
        if (_networkingData.login.isLoggedIn()) {
            request.setRawHeader("Authorization", (QString("Bearer ")+_networkingData.login.JWTToken()).toUtf8());
        } else {
            connect(&_networkingData.login, &AirMapLogin::loginSuccess, this, &AirMapNetworking::_loginSuccess);
            connect(&_networkingData.login, &AirMapLogin::loginFailure, this, &AirMapNetworking::_loginFailure);
            _pendingRequest.type = RequestType::GET;
            _pendingRequest.url = url;
            _pendingRequest.requiresLogin = requiresLogin;
            _networkingData.login.login();
            return;
        }
    }

    QNetworkProxy tProxy;
    tProxy.setType(QNetworkProxy::DefaultProxy);
    _networkingData.networkManager.setProxy(tProxy);

    QNetworkReply* networkReply = _networkingData.networkManager.get(request);
    if (!networkReply) {
        QNetworkReply::NetworkError networkError = QNetworkReply::NetworkError::UnknownNetworkError;
        emit error(networkError, "", "");
        return;
    }

    connect(networkReply, &QNetworkReply::finished, this, &AirMapNetworking::_requestFinished);
}

void AirMapNetworking::_requestFinished(void)
229 230 231
{
    QNetworkReply* reply = qobject_cast<QNetworkReply*>(QObject::sender());

232
    // When an error occurs we still end up here
233
    if (reply->error() != QNetworkReply::NoError) {
234 235 236 237 238 239 240 241 242 243 244 245 246 247
        QByteArray responseBytes = reply->readAll();

        QJsonParseError parseError;
        QJsonDocument responseJson = QJsonDocument::fromJson(responseBytes, &parseError);
        QJsonObject rootObject = responseJson.object();
        QString serverError = "";
        if (rootObject.contains("data")) { // eg. in case of a conflict message
            serverError = rootObject["data"].toObject()["message"].toString();
        } else if (rootObject.contains("error_description")) { // eg. login failure
            serverError = rootObject["error_description"].toString();
        } else if (rootObject.contains("message")) { // eg. api key failure
            serverError = rootObject["message"].toString();
        }
        emit error(reply->error(), reply->errorString(), serverError);
248 249 250 251 252 253 254
        return;
    }

    // Check for redirection
    QVariant redirectionTarget = reply->attribute(QNetworkRequest::RedirectionTargetAttribute);
    if (!redirectionTarget.isNull()) {
        QUrl redirectUrl = reply->url().resolved(redirectionTarget.toUrl());
255
        get(redirectUrl);
256 257 258 259 260 261 262 263
        reply->deleteLater();
        return;
    }

    QByteArray responseBytes = reply->readAll();

    QJsonParseError parseError;
    QJsonDocument responseJson = QJsonDocument::fromJson(responseBytes, &parseError);
264 265 266 267
    if (parseError.error != QJsonParseError::NoError) {
        qCWarning(AirMapManagerLog) << "JSON parse error:" << parseError.errorString();
    }
    emit finished(parseError, responseJson);
268 269 270
}


271

272 273 274 275 276
AirspaceRestrictionManager::AirspaceRestrictionManager(AirMapNetworking::SharedData& sharedData)
    : _networking(sharedData)
{
    connect(&_networking, &AirMapNetworking::finished, this, &AirspaceRestrictionManager::_parseAirspaceJson);
    connect(&_networking, &AirMapNetworking::error, this, &AirspaceRestrictionManager::_error);
277 278
}

279
void AirspaceRestrictionManager::updateROI(const QGeoCoordinate& center, double radiusMeters)
280
{
281 282 283
    if (_state != State::Idle) {
        return;
    }
284

285
    // Build up the polygon for the query
286

287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320
//    QJsonObject     polygonJson;
//
//    polygonJson["type"] = "Polygon";
//
//    QGeoCoordinate left =   _roiCenter.atDistanceAndAzimuth(_roiRadius, -90);
//    QGeoCoordinate right =  _roiCenter.atDistanceAndAzimuth(_roiRadius, 90);
//    QGeoCoordinate top =    _roiCenter.atDistanceAndAzimuth(_roiRadius, 0);
//    QGeoCoordinate bottom = _roiCenter.atDistanceAndAzimuth(_roiRadius, 180);
//
//    QGeoCoordinate topLeft(top.latitude(), left.longitude());
//    QGeoCoordinate topRight(top.latitude(), right.longitude());
//    QGeoCoordinate bottomLeft(bottom.latitude(), left.longitude());
//    QGeoCoordinate bottomRight(bottom.latitude(), left.longitude());
//
//    QJsonValue  coordValue;
//    QJsonArray  rgVertex;
//
//    // GeoJson polygons are right handed and include duplicate first and last vertex
//    JsonHelper::saveGeoJsonCoordinate(topLeft, false /* writeAltitude */, coordValue);
//    rgVertex.append(coordValue);
//    JsonHelper::saveGeoJsonCoordinate(bottomLeft, false /* writeAltitude */, coordValue);
//    rgVertex.append(coordValue);
//    JsonHelper::saveGeoJsonCoordinate(bottomRight, false /* writeAltitude */, coordValue);
//    rgVertex.append(coordValue);
//    JsonHelper::saveGeoJsonCoordinate(topRight, false /* writeAltitude */, coordValue);
//    rgVertex.append(coordValue);
//    JsonHelper::saveGeoJsonCoordinate(topLeft, false /* writeAltitude */, coordValue);
//    rgVertex.append(coordValue);
//
//    QJsonArray rgPolygon;
//    rgPolygon.append(rgVertex);
//
//    polygonJson["coordinates"] = rgPolygon;
//    QJsonDocument polygonJsonDoc(polygonJson);
321 322 323 324 325

    // Build up the http query

    QUrlQuery airspaceQuery;

326 327
    airspaceQuery.addQueryItem(QStringLiteral("latitude"), QString::number(center.latitude(), 'f', 10));
    airspaceQuery.addQueryItem(QStringLiteral("longitude"), QString::number(center.longitude(), 'f', 10));
328
    airspaceQuery.addQueryItem(QStringLiteral("weather"), QStringLiteral("true"));
329
    airspaceQuery.addQueryItem(QStringLiteral("buffer"), QString::number(radiusMeters, 'f', 0));
330

331
    QUrl airMapAirspaceUrl(QStringLiteral("https://api.airmap.com/status/alpha/point"));
332 333
    airMapAirspaceUrl.setQuery(airspaceQuery);

334
    _state = State::RetrieveList;
335
    _networking.get(airMapAirspaceUrl);
336 337
}

338
void AirspaceRestrictionManager::_parseAirspaceJson(QJsonParseError parseError, QJsonDocument airspaceDoc)
339 340 341
{

    QJsonObject rootObject = airspaceDoc.object();
342 343 344 345 346 347 348 349 350

    switch(_state) {
        case State::RetrieveList:
        {
            QSet<QString> advisorySet;
            const QJsonArray& advisoriesArray = rootObject["data"].toObject()["advisories"].toArray();
            for (int i=0; i< advisoriesArray.count(); i++) {
                const QJsonObject& advisoryObject = advisoriesArray[i].toObject();
                QString advisoryId(advisoryObject["id"].toString());
351
                qCDebug(AirMapManagerLog) << "Advisory id: " << advisoryId;
352 353 354 355 356
                advisorySet.insert(advisoryId);
            }

            for (const auto& advisoryId : advisorySet) {
                QUrl url(QStringLiteral("https://api.airmap.com/airspace/v2/")+advisoryId);
357
                _networking.get(url);
358 359 360
            }
            _numAwaitingItems = advisorySet.size();
            _state = State::RetrieveItems;
361
        }
362 363 364 365 366
            break;

        case State::RetrieveItems:
        {
            const QJsonArray& airspaceArray = rootObject["data"].toArray();
367
            for (int i = 0; i < airspaceArray.count(); i++) {
368 369 370 371 372 373
                const QJsonObject& airspaceObject = airspaceArray[i].toObject();
                QString airspaceType(airspaceObject["type"].toString());
                QString airspaceId(airspaceObject["id"].toString());
                QString airspaceName(airspaceObject["name"].toString());
                const QJsonObject& airspaceGeometry(airspaceObject["geometry"].toObject());
                QString geometryType(airspaceGeometry["type"].toString());
374 375
                qCDebug(AirMapManagerLog) << "Airspace ID:" << airspaceId << "name:" << airspaceName << "type:" << airspaceType << "geometry:" << geometryType;

376 377 378 379 380 381 382 383 384 385 386 387 388
                if (geometryType == "Polygon") {

                    const QJsonArray& airspaceCoordinates(airspaceGeometry["coordinates"].toArray()[0].toArray());
                    QString errorString;
                    QmlObjectListModel list;
                    if (JsonHelper::loadPolygon(airspaceCoordinates, list, this, errorString)) {
                        QVariantList polygon;
                        for (int i = 0; i < list.count(); ++i) {
                            polygon.append(QVariant::fromValue(((QGCQGeoCoordinate*)list[i])->coordinate()));
                        }
                        list.clearAndDeleteContents();
                        _nextPolygonList.append(new PolygonAirspaceRestriction(polygon));
                    } else {
389 390
                        //TODO
                        qWarning() << errorString;
391 392 393 394
                    }

                } else {
                    // TODO: are there any circles?
395
                    qWarning() << "Unknown geometry type:" << geometryType;
396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415
                }
            }

            if (--_numAwaitingItems == 0) {
                _polygonList.clearAndDeleteContents();
                _circleList.clearAndDeleteContents();
                for (const auto& circle : _nextcircleList) {
                    _circleList.append(circle);
                }
                _nextcircleList.clear();
                for (const auto& polygon : _nextPolygonList) {
                    _polygonList.append(polygon);
                }
                _nextPolygonList.clear();

                _state = State::Idle;
            }
        }
            break;
        default:
416
            qCDebug(AirMapManagerLog) << "Error: wrong state";
417
            break;
418
    }
419 420 421 422 423 424 425 426 427 428 429 430 431 432

    // https://api.airmap.com/airspace/v2/search API
//    const QJsonArray& airspaceArray = rootObject["data"].toArray();
//    for (int i=0; i< airspaceArray.count(); i++) {
//        const QJsonObject& airspaceObject = airspaceArray[i].toObject();
//        QString airspaceType(airspaceObject["type"].toString());
//        qDebug() << airspaceType;
//        qDebug() << airspaceObject["name"].toString();
//        QGeoCoordinate center(airspaceObject["latitude"].toDouble(), airspaceObject["longitude"].toDouble());
//        qDebug() << center;
//        if (airspaceType == "airport") {
//            _circleList.append(new CircularAirspaceRestriction(center, 5000));
//        }
//    }
433 434
}

435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621
void AirspaceRestrictionManager::_error(QNetworkReply::NetworkError code, const QString& errorString,
        const QString& serverErrorMessage)
{
    qCWarning(AirMapManagerLog) << "AirspaceRestrictionManager::_error" << code << serverErrorMessage;

    if (_state == State::RetrieveItems) {
        if (--_numAwaitingItems == 0) {
            _state = State::Idle;
            // TODO: handle properly: update _polygonList...
        }
    } else {
        _state = State::Idle;
    }
    emit networkError(code, errorString, serverErrorMessage);
}

AirMapFlightManager::AirMapFlightManager(AirMapNetworking::SharedData& sharedData)
    : _networking(sharedData)
{
    connect(&_networking, &AirMapNetworking::finished, this, &AirMapFlightManager::_parseJson);
    connect(&_networking, &AirMapNetworking::error, this, &AirMapFlightManager::_error);
}

void AirMapFlightManager::createFlight(const QList<MissionItem*>& missionItems)
{
    if (!_networking.getLogin().hasCredentials()) {
        qCDebug(AirMapManagerLog) << "Login Credentials not set: will not send flight";
        return;
    }

    if (_state != State::Idle) {
        qCWarning(AirMapManagerLog) << "AirMapFlightManager::createFlight: State not idle";
        return;
    }

    QList<QGeoCoordinate> flight;

    // get the flight trajectory
    for(const auto &item : missionItems) {
        switch(item->command()) {
            case MAV_CMD_NAV_WAYPOINT:
            case MAV_CMD_NAV_LAND:
            case MAV_CMD_NAV_TAKEOFF:
                // TODO: others too?
            {
                // TODO: handle different coordinate frames?
                double lat = item->param5();
                double lon = item->param6();
                double alt = item->param7();
                flight.append(QGeoCoordinate(lat, lon, alt));
            }
                break;
            default:
                break;
        }
    }
    if (flight.empty()) {
        return;
    }

    qCDebug(AirMapManagerLog) << "uploading flight";

    QJsonObject root;
    root.insert("latitude", QJsonValue::fromVariant(flight[0].latitude()));
    root.insert("longitude", QJsonValue::fromVariant(flight[0].longitude()));
    QJsonObject geometryObject;
    geometryObject.insert("type", "LineString");
    QJsonArray coordinatesArray;
    for (const auto& coord : flight) {
        QJsonArray coordinate;
        coordinate.push_back(coord.longitude());
        coordinate.push_back(coord.latitude());
        coordinatesArray.push_back(coordinate);
    }
    geometryObject.insert("coordinates", coordinatesArray);

    root.insert("geometry", geometryObject);

    root.insert("public", QJsonValue::fromVariant(true));
    root.insert("notify", QJsonValue::fromVariant(true));

    _state = State::FlightUpload;

    QUrl url(QStringLiteral("https://api.airmap.com/flight/v2/path"));

    //qCDebug(AirMapManagerLog) << root;
    _networking.post(url, QJsonDocument(root).toJson(), true, true);
}


void AirMapFlightManager::_parseJson(QJsonParseError parseError, QJsonDocument doc)
{

    QJsonObject rootObject = doc.object();

    switch(_state) {
        case State::FlightUpload:
        {
            qDebug() << "flight uploaded:" << rootObject;
            const QJsonObject& dataObject = rootObject["data"].toObject();
            _currentFlightId = dataObject["id"].toString();
            qCDebug(AirMapManagerLog) << "Got Flight ID:" << _currentFlightId;
            _state = State::Idle;
        }
            break;
        default:
            qCDebug(AirMapManagerLog) << "Error: wrong state";
            break;
    }
}

void AirMapFlightManager::_error(QNetworkReply::NetworkError code, const QString& errorString, const QString& serverErrorMessage)
{
    qCWarning(AirMapManagerLog) << "AirMapFlightManager::_error" << code << serverErrorMessage;
    _state = State::Idle;
    emit networkError(code, errorString, serverErrorMessage);
}

AirMapManager::AirMapManager(QGCApplication* app, QGCToolbox* toolbox)
    : QGCTool(app, toolbox), _airspaceRestrictionManager(_networkingData), _flightManager(_networkingData)
{
    _updateTimer.setInterval(2000);
    _updateTimer.setSingleShot(true);
    connect(&_updateTimer, &QTimer::timeout, this, &AirMapManager::_updateToROI);
    connect(&_airspaceRestrictionManager, &AirspaceRestrictionManager::networkError, this, &AirMapManager::_networkError);
    connect(&_flightManager, &AirMapFlightManager::networkError, this, &AirMapManager::_networkError);
}

AirMapManager::~AirMapManager()
{

}

void AirMapManager::setToolbox(QGCToolbox* toolbox)
{
    QGCTool::setToolbox(toolbox);

    _networkingData.airmapAPIKey = toolbox->settingsManager()->appSettings()->airMapKey()->rawValueString();

    // TODO: set login credentials from config
    QString clientID = "";
    QString userName = "";
    QString password = "";
    _networkingData.login.setCredentials(clientID, userName, password);
}

void AirMapManager::setROI(QGeoCoordinate& center, double radiusMeters)
{
    _roiCenter = center;
    _roiRadius = radiusMeters;
    _updateTimer.start();
}

void AirMapManager::_updateToROI(void)
{
    if (!hasAPIKey()) {
        qCDebug(AirMapManagerLog) << "API key not set. Not updating Airspace";
        return;
    }
    _airspaceRestrictionManager.updateROI(_roiCenter, _roiRadius);
}

void AirMapManager::_networkError(QNetworkReply::NetworkError code, const QString& errorString, const QString& serverErrorMessage)
{
    QString errorDetails = "";
    if (code == QNetworkReply::NetworkError::ContentOperationNotPermittedError) {
        errorDetails = " (invalid API key?)";
    } else if (code == QNetworkReply::NetworkError::AuthenticationRequiredError) {
        errorDetails = " (authentication failure)";
    }
    if (serverErrorMessage.length() > 0) {
        // the errorString is a bit verbose and redundant with serverErrorMessage. So we just show the server error.
        qgcApp()->showMessage(QString("AirMap error%1. Response from Server: %2").arg(errorDetails).arg(serverErrorMessage));
    } else {
        qgcApp()->showMessage(QString("AirMap error: %1%2").arg(errorString).arg(errorDetails));
    }
}

void AirMapManager::createFlight(const QList<MissionItem*>& missionItems)
{
    if (!hasAPIKey()) {
        qCDebug(AirMapManagerLog) << "API key not set. Will not create a flight";
        return;
    }
    _flightManager.createFlight(missionItems);
}

622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641
AirspaceRestriction::AirspaceRestriction(QObject* parent)
    : QObject(parent)
{

}

PolygonAirspaceRestriction::PolygonAirspaceRestriction(const QVariantList& polygon, QObject* parent)
    : AirspaceRestriction(parent)
    , _polygon(polygon)
{

}

CircularAirspaceRestriction::CircularAirspaceRestriction(const QGeoCoordinate& center, double radius, QObject* parent)
    : AirspaceRestriction(parent)
    , _center(center)
    , _radius(radius)
{

}