AirMapManager.cc 35.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 "AirMapSettings.h"
17
#include "QGCQGeoCoordinate.h"
18
#include "QGCApplication.h"
19

20 21
#include <airmap/authenticator.h>
#include <airmap/airspaces.h>
22
#include <airmap/evaluation.h>
23 24 25 26
#include <airmap/flight_plans.h>
#include <airmap/flights.h>
#include <airmap/pilots.h>
#include <airmap/telemetry.h>
27

28
using namespace airmap;
29

30
QGC_LOGGING_CATEGORY(AirMapManagerLog, "AirMapManagerLog")
31

32

33
void AirMapSharedState::setSettings(const Settings& settings)
34
{
35
    logout();
36
    _settings = settings;
37 38
}

39
void AirMapSharedState::doRequestWithLogin(const Callback& callback)
40
{
41 42 43 44 45
    if (isLoggedIn()) {
        callback(_loginToken);
    } else {
        login();
        _pendingRequests.enqueue(callback);
46 47
    }
}
48

49
void AirMapSharedState::login()
50
{
51
    if (isLoggedIn() || _isLoginInProgress) {
52 53
        return;
    }
54
    _isLoginInProgress = true;
55

56
    if (_settings.userName == "") { //use anonymous login
57

58 59 60 61 62 63 64 65 66 67 68 69 70
        Authenticator::AuthenticateAnonymously::Params params;
        params.id = "";
        _client->authenticator().authenticate_anonymously(params,
                [this](const Authenticator::AuthenticateAnonymously::Result& result) {
            if (!_isLoginInProgress) { // was logout() called in the meanwhile?
                return;
            }
            if (result) {
                qCDebug(AirMapManagerLog)<<"Successfully authenticated with AirMap: id="<< result.value().id.c_str();
                _loginToken = QString::fromStdString(result.value().id);
                _processPendingRequests();
            } else {
                _pendingRequests.clear();
71 72 73
                QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
                emit error("Failed to authenticate with AirMap",
                        QString::fromStdString(result.error().message()), description);
74 75
            }
        });
76 77 78

    } else {

79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95
        Authenticator::AuthenticateWithPassword::Params params;
        params.oauth.username = _settings.userName.toStdString();
        params.oauth.password = _settings.password.toStdString();
        params.oauth.client_id = _settings.clientID.toStdString();
        params.oauth.device_id = "QGroundControl";
        _client->authenticator().authenticate_with_password(params,
                [this](const Authenticator::AuthenticateWithPassword::Result& result) {
            if (!_isLoginInProgress) { // was logout() called in the meanwhile?
                return;
            }
            if (result) {
                qCDebug(AirMapManagerLog)<<"Successfully authenticated with AirMap: id="<< result.value().id.c_str()<<", access="
                        <<result.value().access.c_str();
                _loginToken = QString::fromStdString(result.value().id);
                _processPendingRequests();
            } else {
                _pendingRequests.clear();
96 97 98
                QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
                emit error("Failed to authenticate with AirMap",
                        QString::fromStdString(result.error().message()), description);
99 100
            }
        });
101 102 103
    }
}

104
void AirMapSharedState::_processPendingRequests()
105
{
106 107
    while (!_pendingRequests.isEmpty()) {
        _pendingRequests.dequeue()(_loginToken);
108 109 110
    }
}

111
void AirMapSharedState::logout()
112
{
113
    _isLoginInProgress = false; // cancel if we're currently trying to login
114

115
    if (!isLoggedIn()) {
116 117
        return;
    }
118 119
    _loginToken = "";
    _pendingRequests.clear();
120 121 122 123

}


124 125
AirMapRestrictionManager::AirMapRestrictionManager(AirMapSharedState& shared)
    : _shared(shared)
126
{
127 128
}

129
void AirMapRestrictionManager::setROI(const QGeoCoordinate& center, double radiusMeters)
130
{
131 132
    if (!_shared.client()) {
        qCDebug(AirMapManagerLog) << "No AirMap client instance. Not updating Airspace";
133 134 135
        return;
    }

136
    if (_state != State::Idle) {
137
        qCWarning(AirMapManagerLog) << "AirMapRestrictionManager::updateROI: state not idle";
138 139
        return;
    }
140
    qCDebug(AirMapManagerLog) << "setting ROI";
141

142 143 144
    _polygonList.clear();
    _circleList.clear();

145 146 147 148 149 150
    _state = State::RetrieveItems;

    Airspaces::Search::Parameters params;
    params.geometry = Geometry::point(center.latitude(), center.longitude());
    params.buffer = radiusMeters;
    params.full = true;
151
    std::weak_ptr<LifetimeChecker> isAlive(_instance);
152
    _shared.client()->airspaces().search(params,
153
            [this, isAlive](const Airspaces::Search::Result& result) {
154

155
        if (!isAlive.lock()) return;
156 157 158 159
        if (_state != State::RetrieveItems) return;

        if (result) {
            const std::vector<Airspace>& airspaces = result.value();
160
            qCDebug(AirMapManagerLog)<<"Successful search. Items:" << airspaces.size();
161 162 163 164 165 166
            for (const auto& airspace : airspaces) {

                const Geometry& geometry = airspace.geometry();
                switch(geometry.type()) {
                    case Geometry::Type::polygon: {
                        const Geometry::Polygon& polygon = geometry.details_for_polygon();
167
                        _addPolygonToList(polygon, _polygonList);
168
                    }
169 170 171
                        break;
                    case Geometry::Type::multi_polygon: {
                        const Geometry::MultiPolygon& multiPolygon = geometry.details_for_multi_polygon();
172 173 174
                        for (const auto& polygon : multiPolygon) {
                            _addPolygonToList(polygon, _polygonList);
                        }
175
                    }
176 177 178 179 180 181 182 183 184 185
                        break;
                    case Geometry::Type::point: {
                        const Geometry::Point& point = geometry.details_for_point();
                        _circleList.append(new CircularAirspaceRestriction(QGeoCoordinate(point.latitude, point.longitude), 0.));
                        // TODO: radius???
                    }
                        break;
                    default:
                        qWarning() << "unsupported geometry type: "<<(int)geometry.type();
                        break;
186 187 188
                }

            }
189

190
        } else {
191
            QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
192
            emit error("Failed to retrieve Geofences",
193
                    QString::fromStdString(result.error().message()), description);
194
        }
195
        emit requestDone(true);
196
        _state = State::Idle;
197
    });
198 199
}

200 201 202
void AirMapRestrictionManager::_addPolygonToList(const airmap::Geometry::Polygon& polygon, QList<PolygonAirspaceRestriction*>& list)
{
    QVariantList polygonArray;
203 204 205 206 207 208
    for (const auto& vertex : polygon.outer_ring.coordinates) {
        QGeoCoordinate coord;
        if (vertex.altitude) {
            coord = QGeoCoordinate(vertex.latitude, vertex.longitude, vertex.altitude.get());
        } else {
            coord = QGeoCoordinate(vertex.latitude, vertex.longitude);
209
        }
210 211 212
        polygonArray.append(QVariant::fromValue(coord));
    }
    list.append(new PolygonAirspaceRestriction(polygonArray));
213

214
    if (polygon.inner_rings.size() > 0) {
215
        // no need to support those (they are rare, and in most cases, there's a more restrictive polygon filling the hole)
216
        qCDebug(AirMapManagerLog) << "Polygon with holes. Size: "<<polygon.inner_rings.size();
217 218 219
    }
}

220 221
AirMapFlightManager::AirMapFlightManager(AirMapSharedState& shared)
    : _shared(shared)
222
{
223
    connect(&_pollTimer, &QTimer::timeout, this, &AirMapFlightManager::_pollBriefing);
224 225 226 227
}

void AirMapFlightManager::createFlight(const QList<MissionItem*>& missionItems)
{
228 229
    if (!_shared.client()) {
        qCDebug(AirMapManagerLog) << "No AirMap client instance. Will not create a flight";
230 231 232 233 234 235 236 237
        return;
    }

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

238
    _flight.reset();
239 240 241 242 243 244 245 246 247 248 249 250 251

    // 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();
252 253 254 255 256 257 258
                _flight.coords.append(QGeoCoordinate(lat, lon, alt));
                if (alt > _flight.maxAltitude) {
                    _flight.maxAltitude = alt;
                }
                if (item->command() == MAV_CMD_NAV_TAKEOFF) {
                    _flight.takeoffCoord = _flight.coords.last();
                }
259 260 261 262 263 264
            }
                break;
            default:
                break;
        }
    }
265 266 267 268 269 270 271 272 273
    if (_flight.coords.empty()) {
        return;
    }

    _flight.maxAltitude += 5; // add a safety buffer


    if (_pilotID == "") {
        // need to get the pilot id before uploading the flight
274
        qCDebug(AirMapManagerLog) << "Getting pilot ID";
275
        _state = State::GetPilotID;
276 277 278 279
        std::weak_ptr<LifetimeChecker> isAlive(_instance);
        _shared.doRequestWithLogin([this, isAlive](const QString& login_token) {
            if (!isAlive.lock()) return;

280 281
            Pilots::Authenticated::Parameters params;
            params.authorization = login_token.toStdString();
282
            _shared.client()->pilots().authenticated(params, [this, isAlive](const Pilots::Authenticated::Result& result) {
283

284
                if (!isAlive.lock()) return;
285 286 287 288 289 290 291 292 293 294 295
                if (_state != State::GetPilotID) return;

                if (result) {
                    _pilotID = QString::fromStdString(result.value().id);
                    qCDebug(AirMapManagerLog) << "Got Pilot ID:"<<_pilotID;
                    _uploadFlight();
                } else {
                    _flightPermitStatus = AirspaceAuthorization::PermitUnknown;
                    emit flightPermitStatusChanged();
                    _state = State::Idle;

296 297 298
                    QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
                    emit error("Failed to create Flight Plan",
                            QString::fromStdString(result.error().message()), description);
299 300 301
                }
            });
        });
302 303 304 305 306 307 308 309
    } else {
        _uploadFlight();
    }

    _flightPermitStatus = AirspaceAuthorization::PermitPending;
    emit flightPermitStatusChanged();
}

310 311 312 313 314 315 316 317 318 319 320
void AirMapFlightManager::_endFirstFlight()
{
    // it could be that AirMap still has an open pending flight, but we don't know the flight ID.
    // As there can only be one, we query the flights that end in the future, and close it if there's one.

    _state = State::EndFirstFlight;

    Flights::Search::Parameters params;
    params.pilot_id = _pilotID.toStdString();
    params.end_after = Clock::universal_time() - Hours{1};

321 322 323
    std::weak_ptr<LifetimeChecker> isAlive(_instance);
    _shared.client()->flights().search(params, [this, isAlive](const Flights::Search::Result& result) {
        if (!isAlive.lock()) return;
324 325
        if (_state != State::EndFirstFlight) return;

326
        if (result && result.value().flights.size() > 0) {
327 328 329 330 331

            Q_ASSERT(_shared.loginToken() != ""); // at this point we know the user is logged in (we queried the pilot id)

            Flights::EndFlight::Parameters params;
            params.authorization = _shared.loginToken().toStdString();
332
            params.id = result.value().flights[0].id; // pick the first flight (TODO: match the vehicle id)
333 334
            _shared.client()->flights().end_flight(params, [this, isAlive](const Flights::EndFlight::Result& result) {
                if (!isAlive.lock()) return;
335 336 337
                if (_state != State::EndFirstFlight) return;

                if (!result) {
338 339 340
                    QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
                    emit error("Failed to end first Flight",
                            QString::fromStdString(result.error().message()), description);
341 342 343 344 345 346 347 348 349 350 351
                }
                _state = State::Idle;
                _uploadFlight();
            });

        } else {
            _state = State::Idle;
            _uploadFlight();
        }
    });
}
352 353 354 355 356 357 358 359 360 361

void AirMapFlightManager::_uploadFlight()
{
    if (_pendingFlightId != "") {
        // we need to end an existing flight first
        _endFlight(_pendingFlightId);
        return;
    }

    if (_noFlightCreatedYet) {
362
        _endFirstFlight();
363
        _noFlightCreatedYet = false;
364 365 366 367 368 369
        return;
    }

    qCDebug(AirMapManagerLog) << "uploading flight";
    _state = State::FlightUpload;

370 371
    std::weak_ptr<LifetimeChecker> isAlive(_instance);
    _shared.doRequestWithLogin([this, isAlive](const QString& login_token) {
372

373
        if (!isAlive.lock()) return;
374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398
        if (_state != State::FlightUpload) return;

        FlightPlans::Create::Parameters params;
        params.max_altitude = _flight.maxAltitude;
        params.buffer = 2.f;
        params.latitude = _flight.takeoffCoord.latitude();
        params.longitude = _flight.takeoffCoord.longitude();
        params.pilot.id = _pilotID.toStdString();
        params.start_time = Clock::universal_time() + Minutes{5};
        params.end_time = Clock::universal_time() + Hours{2}; // TODO: user-configurable?
        params.rulesets = { // TODO: which ones to use?
                "che_drone_rules",
                "che_notam",
                "che_airmap_rules",
                "che_nature_preserve"
                };

        // geometry: LineString
        Geometry::LineString lineString;
        for (const auto& qcoord : _flight.coords) {
            Geometry::Coordinate coord;
            coord.latitude = qcoord.latitude();
            coord.longitude = qcoord.longitude();
            lineString.coordinates.push_back(coord);
        }
399

400 401 402
        params.geometry = Geometry(lineString);
        params.authorization = login_token.toStdString();
        _flight.coords.clear();
403

404 405
        _shared.client()->flight_plans().create_by_polygon(params, [this, isAlive](const FlightPlans::Create::Result& result) {
            if (!isAlive.lock()) return;
406
            if (_state != State::FlightUpload) return;
407

408 409 410
            if (result) {
                _pendingFlightPlan = QString::fromStdString(result.value().id);
                qCDebug(AirMapManagerLog) << "Flight Plan created:"<<_pendingFlightPlan;
411

412
                _checkForValidBriefing();
413

414
            } else {
415 416 417
                QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
                emit error("Flight Plan creation failed",
                        QString::fromStdString(result.error().message()), description);
418
            }
419

420
        });
421

422
    });
423
}
424

425
void AirMapFlightManager::_checkForValidBriefing()
426
{
427 428 429 430
    _state = State::FlightBrief;
    FlightPlans::RenderBriefing::Parameters params;
    params.authorization = _shared.loginToken().toStdString();
    params.id = _pendingFlightPlan.toStdString();
431 432 433
    std::weak_ptr<LifetimeChecker> isAlive(_instance);
    _shared.client()->flight_plans().render_briefing(params, [this, isAlive](const FlightPlans::RenderBriefing::Result& result) {
        if (!isAlive.lock()) return;
434
        if (_state != State::FlightBrief) return;
435

436
        if (result) {
437
            bool allValid = true;
438 439
            for (const auto& validation : result.value().evaluation.validations) {
                if (validation.status != Evaluation::Validation::Status::valid) {
440 441
                    emit error(QString("%1 registration identifier is invalid: %2").arg(
                        QString::fromStdString(validation.authority.name)).arg(QString::fromStdString(validation.message)), "", "");
442 443 444 445
                    allValid = false;
                }
            }
            if (allValid) {
446
                _submitPendingFlightPlan();
447 448 449 450 451
            } else {
                _flightPermitStatus = AirspaceAuthorization::PermitRejected;
                emit flightPermitStatusChanged();
                _state = State::Idle;
            }
452 453

        } else {
454 455 456 457
            QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
            emit error("Brief Request failed",
                    QString::fromStdString(result.error().message()), description);
            _state = State::Idle;
458
        }
459 460 461 462 463 464 465 466 467
    });
}

void AirMapFlightManager::_submitPendingFlightPlan()
{
    _state = State::FlightSubmit;
    FlightPlans::Submit::Parameters params;
    params.authorization = _shared.loginToken().toStdString();
    params.id = _pendingFlightPlan.toStdString();
468 469 470
    std::weak_ptr<LifetimeChecker> isAlive(_instance);
    _shared.client()->flight_plans().submit(params, [this, isAlive](const FlightPlans::Submit::Result& result) {
        if (!isAlive.lock()) return;
471 472 473 474 475 476 477 478
        if (_state != State::FlightSubmit) return;

        if (result) {
            _pendingFlightId = QString::fromStdString(result.value().flight_id.get());
            _state = State::FlightPolling;
            _pollBriefing();

        } else {
479 480 481 482
            QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
            emit error("Failed to submit Flight Plan",
                    QString::fromStdString(result.error().message()), description);
            _state = State::Idle;
483
        }
484 485
    });
}
486

487 488 489 490 491 492 493 494 495 496
void AirMapFlightManager::_pollBriefing()
{
    if (_state != State::FlightPolling) {
        qCWarning(AirMapManagerLog) << "AirMapFlightManager::_pollBriefing: not in polling state";
        return;
    }

    FlightPlans::RenderBriefing::Parameters params;
    params.authorization = _shared.loginToken().toStdString();
    params.id = _pendingFlightPlan.toStdString();
497 498 499
    std::weak_ptr<LifetimeChecker> isAlive(_instance);
    _shared.client()->flight_plans().render_briefing(params, [this, isAlive](const FlightPlans::RenderBriefing::Result& result) {
        if (!isAlive.lock()) return;
500 501 502 503 504
        if (_state != State::FlightPolling) return;

        if (result) {
            const FlightPlan::Briefing& briefing = result.value();
            qCDebug(AirMapManagerLog) << "flight polling/briefing response";
505 506 507
            bool rejected = false;
            bool accepted = false;
            bool pending = false;
508
            for (const auto& authorization : briefing.evaluation.authorizations) {
509
                switch (authorization.status) {
510 511
                case Evaluation::Authorization::Status::accepted:
                case Evaluation::Authorization::Status::accepted_upon_submission:
512
                    accepted = true;
513
                    break;
514 515
                case Evaluation::Authorization::Status::rejected:
                case Evaluation::Authorization::Status::rejected_upon_submission:
516
                    rejected = true;
517
                    break;
518
                case Evaluation::Authorization::Status::pending:
519
                    pending = true;
520
                    break;
521 522 523
                }
            }

524
            if (briefing.evaluation.authorizations.size() == 0) {
525
                // if we don't get any authorizations, we assume it's accepted
526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545
                accepted = true;
            }

            qCDebug(AirMapManagerLog) << "flight approval: accepted=" << accepted << "rejected" << rejected << "pending" << pending;

            if ((rejected || accepted) && !pending) {
                if (rejected) { // rejected has priority
                    _flightPermitStatus = AirspaceAuthorization::PermitRejected;
                } else {
                    _flightPermitStatus = AirspaceAuthorization::PermitAccepted;
                }
                _currentFlightId = _pendingFlightId;
                _pendingFlightPlan = "";
                emit flightPermitStatusChanged();
                _state = State::Idle;
            } else {
                // wait until we send the next polling request
                _pollTimer.setSingleShot(true);
                _pollTimer.start(2000);
            }
546
        } else {
547 548 549 550
            QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
            emit error("Brief Request failed",
                    QString::fromStdString(result.error().message()), description);
            _state = State::Idle;
551
        }
552
    });
553 554
}

555
void AirMapFlightManager::endFlight()
556
{
557 558
    if (_currentFlightId.length() == 0) {
        return;
559
    }
560 561 562 563 564
    if (_state != State::Idle) {
        qCWarning(AirMapManagerLog) << "AirMapFlightManager::endFlight: State not idle";
        return;
    }
    _endFlight(_currentFlightId);
565

566 567
    _flightPermitStatus = AirspaceAuthorization::PermitUnknown;
    emit flightPermitStatusChanged();
568 569
}

570
void AirMapFlightManager::_endFlight(const QString& flightID)
571
{
572 573 574 575 576 577 578 579 580
    qCDebug(AirMapManagerLog) << "ending flight" << flightID;

    _state = State::FlightEnd;

    Q_ASSERT(_shared.loginToken() != ""); // Since we have a flight ID, we need to be logged in

    Flights::EndFlight::Parameters params;
    params.authorization = _shared.loginToken().toStdString();
    params.id = flightID.toStdString();
581 582 583
    std::weak_ptr<LifetimeChecker> isAlive(_instance);
    _shared.client()->flights().end_flight(params, [this, isAlive](const Flights::EndFlight::Result& result) {
        if (!isAlive.lock()) return;
584 585 586 587 588 589 590 591 592 593 594
        if (_state != State::FlightEnd) return;

        _state = State::Idle;
        _pendingFlightId = "";
        _pendingFlightPlan = "";
        _currentFlightId = "";
        if (result) {
            if (!_flight.coords.empty()) {
                _uploadFlight();
            }
        } else {
595 596 597
            QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
            emit error("Failed to end Flight",
                    QString::fromStdString(result.error().message()), description);
598 599
        }
    });
600
}
601 602 603 604


AirMapTelemetry::AirMapTelemetry(AirMapSharedState& shared)
: _shared(shared)
605 606 607 608 609 610 611 612 613
{
}

void AirMapTelemetry::vehicleMavlinkMessageReceived(const mavlink_message_t& message)
{
    switch (message.msgid) {
    case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
        _handleGlobalPositionInt(message);
        break;
614 615 616
    case MAVLINK_MSG_ID_GPS_RAW_INT:
        _handleGPSRawInt(message);
        break;
617 618 619 620
    }

}

621
bool AirMapTelemetry::isTelemetryStreaming() const
622
{
623
    return _state == State::Streaming;
624 625 626 627
}

void AirMapTelemetry::_handleGPSRawInt(const mavlink_message_t& message)
{
628
    if (!isTelemetryStreaming()) {
629 630 631 632 633 634 635 636 637 638 639 640 641
        return;
    }

    mavlink_gps_raw_int_t gps_raw;
    mavlink_msg_gps_raw_int_decode(&message, &gps_raw);

    if (gps_raw.eph == UINT16_MAX) {
        _lastHdop = 1.f;
    } else {
        _lastHdop = gps_raw.eph / 100.f;
    }
}

642 643
void AirMapTelemetry::_handleGlobalPositionInt(const mavlink_message_t& message)
{
644
    if (!isTelemetryStreaming()) {
645 646 647 648 649 650
        return;
    }

    mavlink_global_position_int_t globalPosition;
    mavlink_msg_global_position_int_decode(&message, &globalPosition);

651 652 653 654 655 656 657 658 659 660 661 662 663 664
    Telemetry::Position position{
        milliseconds_since_epoch(Clock::universal_time()),
        (double) globalPosition.lat / 1e7,
        (double) globalPosition.lon / 1e7,
        (float) globalPosition.alt / 1000.f,
        (float) globalPosition.relative_alt / 1000.f,
        _lastHdop
    };
    Telemetry::Speed speed{
        milliseconds_since_epoch(Clock::universal_time()),
        globalPosition.vx / 100.f,
        globalPosition.vy / 100.f,
        globalPosition.vz / 100.f
    };
665

666 667 668 669
    Flight flight;
    flight.id = _flightID.toStdString();
    _shared.client()->telemetry().submit_updates(flight, _key,
        {Telemetry::Update{position}, Telemetry::Update{speed}});
670 671 672 673 674 675 676 677 678 679 680 681 682 683 684

}

void AirMapTelemetry::startTelemetryStream(const QString& flightID)
{
    if (_state != State::Idle) {
        qCWarning(AirMapManagerLog) << "Not starting telemetry: not in idle state:" << (int)_state;
        return;
    }

    qCInfo(AirMapManagerLog) << "Starting Telemetry stream with flightID" << flightID;

    _state = State::StartCommunication;
    _flightID = flightID;

685 686 687
    Flights::StartFlightCommunications::Parameters params;
    params.authorization = _shared.loginToken().toStdString();
    params.id = _flightID.toStdString();
688 689 690
    std::weak_ptr<LifetimeChecker> isAlive(_instance);
    _shared.client()->flights().start_flight_communications(params, [this, isAlive](const Flights::StartFlightCommunications::Result& result) {
        if (!isAlive.lock()) return;
691 692 693 694 695 696 697
        if (_state != State::StartCommunication) return;

        if (result) {
            _key = result.value().key;
            _state = State::Streaming;
        } else {
            _state = State::Idle;
698 699 700
            QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
            emit error("Failed to start telemetry streaming",
                    QString::fromStdString(result.error().message()), description);
701 702
        }
    });
703 704 705 706 707 708 709 710 711 712
}

void AirMapTelemetry::stopTelemetryStream()
{
    if (_state == State::Idle) {
        return;
    }
    qCInfo(AirMapManagerLog) << "Stopping Telemetry stream with flightID" << _flightID;

    _state = State::EndCommunication;
713 714 715
    Flights::EndFlightCommunications::Parameters params;
    params.authorization = _shared.loginToken().toStdString();
    params.id = _flightID.toStdString();
716 717
    std::weak_ptr<LifetimeChecker> isAlive(_instance);
    _shared.client()->flights().end_flight_communications(params, [this, isAlive](const Flights::EndFlightCommunications::Result& result) {
718
        Q_UNUSED(result);
719
        if (!isAlive.lock()) return;
720 721 722 723 724
        if (_state != State::EndCommunication) return;

        _key = "";
        _state = State::Idle;
    });
725 726
}

727
AirMapTrafficMonitor::~AirMapTrafficMonitor()
728
{
729
    stop();
730 731
}

732
void AirMapTrafficMonitor::startConnection(const QString& flightID)
733
{
734
    _flightID = flightID;
735 736 737
    std::weak_ptr<LifetimeChecker> isAlive(_instance);
    auto handler = [this, isAlive](const Traffic::Monitor::Result& result) {
        if (!isAlive.lock()) return;
738 739 740 741 742 743
        if (result) {
            _monitor = result.value();
            _subscriber = std::make_shared<Traffic::Monitor::FunctionalSubscriber>(
                    std::bind(&AirMapTrafficMonitor::_update, this, std::placeholders::_1,  std::placeholders::_2));
            _monitor->subscribe(_subscriber);
        } else {
744 745 746
            QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
            emit error("Failed to start Traffic Monitoring",
                    QString::fromStdString(result.error().message()), description);
747 748
        }
    };
749

750 751
    Traffic::Monitor::Params params{flightID.toStdString(), _shared.loginToken().toStdString()};
    _shared.client()->traffic().monitor(params, handler);
752 753
}

754
void AirMapTrafficMonitor::_update(Traffic::Update::Type type, const std::vector<Traffic::Update>& update)
755
{
756
    qCDebug(AirMapManagerLog) << "Traffic update with" << update.size() << "elements";
757

758 759
    if (type != Traffic::Update::Type::situational_awareness)
        return; // currently we're only interested in situational awareness
760

761 762 763 764 765
    for (const auto& traffic : update) {
        QString traffic_id = QString::fromStdString(traffic.id);
        QString vehicle_id = QString::fromStdString(traffic.aircraft_id);
        emit trafficUpdate(traffic_id, vehicle_id, QGeoCoordinate(traffic.latitude, traffic.longitude, traffic.altitude),
                traffic.heading);
766 767 768
    }
}

769 770 771 772 773 774 775 776
void AirMapTrafficMonitor::stop()
{
    if (_monitor) {
        _monitor->unsubscribe(_subscriber);
        _subscriber.reset();
        _monitor.reset();
    }
}
777

778
AirMapManagerPerVehicle::AirMapManagerPerVehicle(AirMapSharedState& shared, const Vehicle& vehicle,
779
        QGCToolbox& toolbox)
780 781
    : AirspaceManagerPerVehicle(vehicle), _shared(shared),
    _flightManager(shared), _telemetry(shared), _trafficMonitor(shared),
782
    _toolbox(toolbox)
783
{
784 785 786 787
    connect(&_flightManager, &AirMapFlightManager::flightPermitStatusChanged,
            this, &AirMapManagerPerVehicle::flightPermitStatusChanged);
    connect(&_flightManager, &AirMapFlightManager::flightPermitStatusChanged,
            this, &AirMapManagerPerVehicle::_flightPermitStatusChanged);
788 789 790
    connect(&_flightManager, &AirMapFlightManager::error, this, &AirMapManagerPerVehicle::error);
    connect(&_telemetry, &AirMapTelemetry::error, this, &AirMapManagerPerVehicle::error);
    connect(&_trafficMonitor, &AirMapTrafficMonitor::error, this, &AirMapManagerPerVehicle::error);
791
    connect(&_trafficMonitor, &AirMapTrafficMonitor::trafficUpdate, this, &AirspaceManagerPerVehicle::trafficUpdate);
792 793
}

794
void AirMapManagerPerVehicle::createFlight(const QList<MissionItem*>& missionItems)
795
{
796 797
    if (!_shared.client()) {
        qCDebug(AirMapManagerLog) << "No AirMap client instance. Will not create a flight";
798
        return;
799
    }
800 801
    _flightManager.createFlight(missionItems);
}
802

803 804 805
AirspaceAuthorization::PermitStatus AirMapManagerPerVehicle::flightPermitStatus() const
{
    return _flightManager.flightPermitStatus();
806 807
}

808
void AirMapManagerPerVehicle::startTelemetryStream()
809
{
810 811 812 813
    if (_flightManager.flightID() != "") {
        _telemetry.startTelemetryStream(_flightManager.flightID());
    }
}
814

815 816 817
void AirMapManagerPerVehicle::stopTelemetryStream()
{
    _telemetry.stopTelemetryStream();
818 819
}

820
bool AirMapManagerPerVehicle::isTelemetryStreaming() const
821
{
822
    return _telemetry.isTelemetryStreaming();
823 824
}

825
void AirMapManagerPerVehicle::endFlight()
826
{
827
    _flightManager.endFlight();
828
    _trafficMonitor.stop();
829
}
830

831 832 833 834
void AirMapManagerPerVehicle::vehicleMavlinkMessageReceived(const mavlink_message_t& message)
{
    if (isTelemetryStreaming()) {
        _telemetry.vehicleMavlinkMessageReceived(message);
835 836 837
    }
}

838
void AirMapManagerPerVehicle::_flightPermitStatusChanged()
839
{
840 841 842 843
    // activate traffic alerts
    if (_flightManager.flightPermitStatus() == AirspaceAuthorization::PermitAccepted) {
        qCDebug(AirMapManagerLog) << "Subscribing to Traffic Alerts";
        // since we already created the flight, we know that we have a valid login token
844
        _trafficMonitor.startConnection(_flightManager.flightID());
845 846 847
    }
}

848 849 850
AirMapManager::AirMapManager(QGCApplication* app, QGCToolbox* toolbox)
    : AirspaceManager(app, toolbox)
{
851 852 853 854 855 856 857 858 859 860 861 862 863 864 865
    _logger = std::make_shared<qt::Logger>();
    qt::register_types(); // TODO: still needed?
    _logger->logging_category().setEnabled(QtDebugMsg, true);
    _logger->logging_category().setEnabled(QtInfoMsg, true);
    _logger->logging_category().setEnabled(QtWarningMsg, true);
    _dispatchingLogger = std::make_shared<qt::DispatchingLogger>(_logger);

    connect(&_shared, &AirMapSharedState::error, this, &AirMapManager::_error);
}

AirMapManager::~AirMapManager()
{
    if (_shared.client()) {
        delete _shared.client();
    }
866 867
}

868 869
void AirMapManager::setToolbox(QGCToolbox* toolbox)
{
870
    AirspaceManager::setToolbox(toolbox);
871
    AirMapSettings* ap = toolbox->settingsManager()->airMapSettings();
872 873 874 875 876 877

    connect(ap->apiKey(),   &Fact::rawValueChanged, this, &AirMapManager::_settingsChanged);
    connect(ap->clientID(),   &Fact::rawValueChanged, this, &AirMapManager::_settingsChanged);
    connect(ap->userName(),   &Fact::rawValueChanged, this, &AirMapManager::_settingsChanged);
    connect(ap->password(),   &Fact::rawValueChanged, this, &AirMapManager::_settingsChanged);

878 879 880 881 882 883
    _settingsChanged();

}

void AirMapManager::_error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails)
{
884 885
    qCDebug(AirMapManagerLog) << "Error: "<<what<<", msg: "<<airmapdMessage<<", details: "<<airmapdDetails;
    qgcApp()->showMessage(QString("AirMap Error: %1. %2").arg(what).arg(airmapdMessage));
886 887
}

888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925
void AirMapManager::requestWeatherUpdate(const QGeoCoordinate& coordinate)
{
    if (!_shared.client()) {
        qCDebug(AirMapManagerLog) << "No AirMap client instance. Not updating Weather information";
        emit weatherUpdate(false, QGeoCoordinate{}, WeatherInformation{});
        return;
    }

    Status::GetStatus::Parameters params;
    params.longitude = coordinate.longitude();
    params.latitude = coordinate.latitude();
    params.weather = true;

    _shared.client()->status().get_status_by_point(params, [this, coordinate](const Status::GetStatus::Result& result) {

        if (result) {

            const Status::Weather& weather = result.value().weather;
            WeatherInformation weatherUpdateInfo;

            weatherUpdateInfo.condition = QString::fromStdString(weather.condition);
            weatherUpdateInfo.icon = QString::fromStdString(weather.icon);
            weatherUpdateInfo.windHeading = weather.wind.heading;
            weatherUpdateInfo.windSpeed = weather.wind.speed;
            weatherUpdateInfo.windGusting = weather.wind.gusting;
            weatherUpdateInfo.temperature = weather.temperature;
            weatherUpdateInfo.humidity = weather.humidity;
            weatherUpdateInfo.visibility = weather.visibility;
            weatherUpdateInfo.precipitation = weather.precipitation;
            emit weatherUpdate(true, coordinate, weatherUpdateInfo);

        } else {
            emit weatherUpdate(false, coordinate, WeatherInformation{});
        }
    });

}

926 927 928 929 930
void AirMapManager::_settingsChanged()
{
    qCDebug(AirMapManagerLog) << "AirMap settings changed";

    AirMapSettings* ap = _toolbox->settingsManager()->airMapSettings();
931

932 933 934 935 936 937 938
    AirMapSharedState::Settings settings;
    settings.apiKey = ap->apiKey()->rawValueString();
    bool apiKeyChanged = settings.apiKey != _shared.settings().apiKey;
    settings.clientID = ap->clientID()->rawValueString();
    settings.userName = ap->userName()->rawValueString();
    settings.password = ap->password()->rawValueString();
    _shared.setSettings(settings);
939

940 941 942 943
    // need to re-create the client if the API key changed
    if (_shared.client() && apiKeyChanged) {
        delete _shared.client();
        _shared.setClient(nullptr);
944
    }
945 946 947 948 949 950 951 952 953 954 955 956 957 958 959


    if (!_shared.client() && settings.apiKey != "") {
        qCDebug(AirMapManagerLog) << "Creating AirMap client";

        auto credentials    = Credentials{};
        credentials.api_key = _shared.settings().apiKey.toStdString();
        auto configuration  = Client::default_staging_configuration(credentials);
        qt::Client::create(configuration, _dispatchingLogger, this, [this, ap](const qt::Client::CreateResult& result) {
            if (result) {
                qCDebug(AirMapManagerLog) << "Successfully created airmap::qt::Client instance";
                _shared.setClient(result.value());

            } else {
                qWarning("Failed to create airmap::qt::Client instance");
960 961 962
                QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
                _error("Failed to create airmap::qt::Client instance",
                        QString::fromStdString(result.error().message()), description);
963 964
            }
        });
965 966 967
    }
}

968
AirspaceManagerPerVehicle* AirMapManager::instantiateVehicle(const Vehicle& vehicle)
969
{
970
    AirMapManagerPerVehicle* manager = new AirMapManagerPerVehicle(_shared, vehicle, *_toolbox);
971
    connect(manager, &AirMapManagerPerVehicle::error, this, &AirMapManager::_error);
972
    return manager;
973 974
}

975
AirspaceRestrictionProvider* AirMapManager::instantiateRestrictionProvider()
976
{
977 978
    AirMapRestrictionManager* restrictionManager = new AirMapRestrictionManager(_shared);
    connect(restrictionManager, &AirMapRestrictionManager::error, this, &AirMapManager::_error);
979
    return restrictionManager;
980 981
}