AirMapManager.cc 32 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 22 23 24 25
#include <airmap/authenticator.h>
#include <airmap/airspaces.h>
#include <airmap/flight_plans.h>
#include <airmap/flights.h>
#include <airmap/pilots.h>
#include <airmap/telemetry.h>
26

27
using namespace airmap;
28

29
QGC_LOGGING_CATEGORY(AirMapManagerLog, "AirMapManagerLog")
30

31

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

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

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

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

57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77
        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();
                try {
                    std::rethrow_exception(result.error());
                } catch (const std::exception& e) {
                    // TODO: emit signal
                    emit error("Failed to authenticate with AirMap", e.what(), "");
                }
            }
        });
78 79 80

    } else {

81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105
        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();
                try {
                    std::rethrow_exception(result.error());
                } catch (const std::exception& e) {
                    // TODO: proper error handling
                    emit error("Failed to authenticate with AirMap", e.what(), "");
                }
            }
        });
106 107 108
    }
}

109
void AirMapSharedState::_processPendingRequests()
110
{
111 112
    while (!_pendingRequests.isEmpty()) {
        _pendingRequests.dequeue()(_loginToken);
113 114 115
    }
}

116
void AirMapSharedState::logout()
117
{
118
    _isLoginInProgress = false; // cancel if we're currently trying to login
119

120
    if (!isLoggedIn()) {
121 122
        return;
    }
123 124
    _loginToken = "";
    _pendingRequests.clear();
125 126 127 128

}


129 130
AirMapRestrictionManager::AirMapRestrictionManager(AirMapSharedState& shared)
    : _shared(shared)
131
{
132 133
    //connect(&_networking, &AirMapNetworking::finished, this, &AirMapRestrictionManager::_parseAirspaceJson);
    //connect(&_networking, &AirMapNetworking::error, this, &AirMapRestrictionManager::_error);
134 135
}

136
void AirMapRestrictionManager::setROI(const QGeoCoordinate& center, double radiusMeters)
137
{
138 139
    if (!_shared.client()) {
        qCDebug(AirMapManagerLog) << "No AirMap client instance. Not updating Airspace";
140 141 142
        return;
    }

143
    if (_state != State::Idle) {
144
        qCWarning(AirMapManagerLog) << "AirMapRestrictionManager::updateROI: state not idle";
145 146
        return;
    }
147
    qCDebug(AirMapManagerLog) << "setting ROI";
148

149 150 151
    _polygonList.clear();
    _circleList.clear();

152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183
    _state = State::RetrieveItems;

    Airspaces::Search::Parameters params;
    params.geometry = Geometry::point(center.latitude(), center.longitude());
    params.buffer = radiusMeters;
    params.full = true;
    _shared.client()->airspaces().search(params,
            [this](const Airspaces::Search::Result& result) {

        if (_state != State::RetrieveItems) return;

        if (result) {
            const std::vector<Airspace>& airspaces = result.value();
            qCDebug(AirMapManagerLog)<<"Successful search: " << airspaces.size();
            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();
                        QVariantList polygonArray;
                        if (polygon.size() == 1) {
                            for (const auto& vertex : polygon[0].coordinates) {
                                QGeoCoordinate coord;
                                if (vertex.altitude) {
                                    coord = QGeoCoordinate(vertex.latitude, vertex.longitude, vertex.altitude.get());
                                } else {
                                    coord = QGeoCoordinate(vertex.latitude, vertex.longitude);
                                }
                                polygonArray.append(QVariant::fromValue(coord));
                            }
                            _polygonList.append(new PolygonAirspaceRestriction(polygonArray));
184

185 186 187
                        } else {
                            // TODO: support that?
                            qWarning() << "Empty polygon, or Polygon with holes. Size: "<<polygon.size();
188 189
                        }
                    }
190 191 192 193 194
                        break;
                    case Geometry::Type::multi_polygon: {
                        const Geometry::MultiPolygon& multiPolygon = geometry.details_for_multi_polygon();
                        qWarning() << "multi polygon "<<multiPolygon.size();
                        // TODO
195
                    }
196 197 198 199 200 201 202 203 204 205
                        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;
206 207 208
                }

            }
209

210 211 212 213 214 215 216
        } else {
            try {
                std::rethrow_exception(result.error());
            } catch (const std::exception& e) {
                // TODO: proper error handling
                emit error("Failed to authenticate with AirMap", e.what(), "");
            }
217
        }
218
        emit requestDone(true);
219
        _state = State::Idle;
220
    });
221 222
}

223 224
AirMapFlightManager::AirMapFlightManager(AirMapSharedState& shared)
    : _shared(shared)
225
{
226
    connect(&_pollTimer, &QTimer::timeout, this, &AirMapFlightManager::_pollBriefing);
227 228 229 230
}

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

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

241
    _flight.reset();
242 243 244 245 246 247 248 249 250 251 252 253 254

    // 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();
255 256 257 258 259 260 261
                _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();
                }
262 263 264 265 266 267
            }
                break;
            default:
                break;
        }
    }
268 269 270 271 272 273 274 275 276
    if (_flight.coords.empty()) {
        return;
    }

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


    if (_pilotID == "") {
        // need to get the pilot id before uploading the flight
277
        qCDebug(AirMapManagerLog) << "Getting pilot ID";
278
        _state = State::GetPilotID;
279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303
        _shared.doRequestWithLogin([this](const QString& login_token) {
            Pilots::Authenticated::Parameters params;
            params.authorization = login_token.toStdString();
            _shared.client()->pilots().authenticated(params, [this](const Pilots::Authenticated::Result& result) {

                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;

                    try {
                        std::rethrow_exception(result.error());
                    } catch (const std::exception& e) {
                        // TODO: proper error handling
                        emit error("Failed to create Flight Plan", e.what(), "");
                    }
                }
            });
        });
304 305 306 307 308 309 310 311
    } else {
        _uploadFlight();
    }

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

312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353
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};

    _shared.client()->flights().search(params, [this](const Flights::Search::Result& result) {
        if (_state != State::EndFirstFlight) return;

        if (result && result.value().size() > 0) {

            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();
            params.id = result.value()[0].id; // pick the first flight (TODO: match the vehicle id)
            _shared.client()->flights().end_flight(params, [this](const Flights::EndFlight::Result& result) {
                if (_state != State::EndFirstFlight) return;

                if (!result) {
                    try {
                        std::rethrow_exception(result.error());
                    } catch (const std::exception& e) {
                        // TODO: emit signal
                        emit error("Failed to end first Flight", e.what(), "");
                    }
                }
                _state = State::Idle;
                _uploadFlight();
            });

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

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

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

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

372 373 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
    _shared.doRequestWithLogin([this](const QString& login_token) {

        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](const FlightPlans::Create::Result& result) {
            if (_state != State::FlightUpload) return;
406

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

411
                _checkForValidBriefing();
412

413 414 415 416
            } else {
                // TODO
                qCDebug(AirMapManagerLog) << "Flight Plan creation failed";
            }
417

418
        });
419

420
    });
421
}
422

423
void AirMapFlightManager::_checkForValidBriefing()
424
{
425 426 427 428 429 430
    _state = State::FlightBrief;
    FlightPlans::RenderBriefing::Parameters params;
    params.authorization = _shared.loginToken().toStdString();
    params.id = _pendingFlightPlan.toStdString();
    _shared.client()->flight_plans().render_briefing(params, [this](const FlightPlans::RenderBriefing::Result& result) {
        if (_state != State::FlightBrief) return;
431

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

        } else {
            // TODO
451
        }
452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470
    });
}

void AirMapFlightManager::_submitPendingFlightPlan()
{
    _state = State::FlightSubmit;
    FlightPlans::Submit::Parameters params;
    params.authorization = _shared.loginToken().toStdString();
    params.id = _pendingFlightPlan.toStdString();
    _shared.client()->flight_plans().submit(params, [this](const FlightPlans::Submit::Result& result) {
        if (_state != State::FlightSubmit) return;

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

        } else {
            // TODO
471
        }
472 473
    });
}
474

475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490
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();
    _shared.client()->flight_plans().render_briefing(params, [this](const FlightPlans::RenderBriefing::Result& result) {
        if (_state != State::FlightPolling) return;

        if (result) {
            const FlightPlan::Briefing& briefing = result.value();
            qCDebug(AirMapManagerLog) << "flight polling/briefing response";
491 492 493
            bool rejected = false;
            bool accepted = false;
            bool pending = false;
494 495 496 497
            for (const auto& authorization : briefing.authorizations) {
                switch (authorization.status) {
                case FlightPlan::Briefing::Authorization::Status::accepted:
                case FlightPlan::Briefing::Authorization::Status::accepted_upon_submission:
498
                    accepted = true;
499 500 501
                    break;
                case FlightPlan::Briefing::Authorization::Status::rejected:
                case FlightPlan::Briefing::Authorization::Status::rejected_upon_submission:
502
                    rejected = true;
503 504
                    break;
                case FlightPlan::Briefing::Authorization::Status::pending:
505
                    pending = true;
506
                    break;
507 508 509
                }
            }

510
            if (briefing.authorizations.size() == 0) {
511
                // if we don't get any authorizations, we assume it's accepted
512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531
                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);
            }
532 533
        } else {
            // TODO: error handling
534
        }
535
    });
536 537
}

538
void AirMapFlightManager::endFlight()
539
{
540 541
    if (_currentFlightId.length() == 0) {
        return;
542
    }
543 544 545 546 547
    if (_state != State::Idle) {
        qCWarning(AirMapManagerLog) << "AirMapFlightManager::endFlight: State not idle";
        return;
    }
    _endFlight(_currentFlightId);
548

549 550
    _flightPermitStatus = AirspaceAuthorization::PermitUnknown;
    emit flightPermitStatusChanged();
551 552
}

553
void AirMapFlightManager::_endFlight(const QString& flightID)
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
    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();
    _shared.client()->flights().end_flight(params, [this](const Flights::EndFlight::Result& result) {
        if (_state != State::FlightEnd) return;

        _state = State::Idle;
        _pendingFlightId = "";
        _pendingFlightPlan = "";
        _currentFlightId = "";
        if (result) {
            if (!_flight.coords.empty()) {
                _uploadFlight();
            }
        } else {
            try {
                std::rethrow_exception(result.error());
            } catch (const std::exception& e) {
                // TODO: emit signal
                emit error("Failed to end Flight", e.what(), "");
            }
        }
    });
584
}
585 586 587 588


AirMapTelemetry::AirMapTelemetry(AirMapSharedState& shared)
: _shared(shared)
589 590 591 592 593 594 595 596 597
{
}

void AirMapTelemetry::vehicleMavlinkMessageReceived(const mavlink_message_t& message)
{
    switch (message.msgid) {
    case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
        _handleGlobalPositionInt(message);
        break;
598 599 600
    case MAVLINK_MSG_ID_GPS_RAW_INT:
        _handleGPSRawInt(message);
        break;
601 602 603 604
    }

}

605
bool AirMapTelemetry::isTelemetryStreaming() const
606
{
607
    return _state == State::Streaming;
608 609 610 611
}

void AirMapTelemetry::_handleGPSRawInt(const mavlink_message_t& message)
{
612
    if (!isTelemetryStreaming()) {
613 614 615 616 617 618 619 620 621 622 623 624 625
        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;
    }
}

626 627
void AirMapTelemetry::_handleGlobalPositionInt(const mavlink_message_t& message)
{
628
    if (!isTelemetryStreaming()) {
629 630 631 632 633 634
        return;
    }

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

635 636 637 638 639 640 641 642 643 644 645 646 647 648
    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
    };
649

650 651 652 653
    Flight flight;
    flight.id = _flightID.toStdString();
    _shared.client()->telemetry().submit_updates(flight, _key,
        {Telemetry::Update{position}, Telemetry::Update{speed}});
654 655 656 657 658 659 660 661 662 663 664 665 666 667 668

}

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;

669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687
    Flights::StartFlightCommunications::Parameters params;
    params.authorization = _shared.loginToken().toStdString();
    params.id = _flightID.toStdString();
    _shared.client()->flights().start_flight_communications(params, [this](const Flights::StartFlightCommunications::Result& result) {
        if (_state != State::StartCommunication) return;

        if (result) {
            _key = result.value().key;
            _state = State::Streaming;
        } else {
            _state = State::Idle;
            try {
                std::rethrow_exception(result.error());
            } catch (const std::exception& e) {
                // TODO: emit signal
                emit error("Failed to start telemetry streaming", e.what(), "");
            }
        }
    });
688 689 690 691 692 693 694 695 696 697
}

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

    _state = State::EndCommunication;
698 699 700 701 702 703 704 705 706 707
    Flights::EndFlightCommunications::Parameters params;
    params.authorization = _shared.loginToken().toStdString();
    params.id = _flightID.toStdString();
    _shared.client()->flights().end_flight_communications(params, [this](const Flights::EndFlightCommunications::Result& result) {
        Q_UNUSED(result);
        if (_state != State::EndCommunication) return;

        _key = "";
        _state = State::Idle;
    });
708 709
}

710
AirMapTrafficMonitor::~AirMapTrafficMonitor()
711
{
712
    stop();
713 714
}

715
void AirMapTrafficMonitor::startConnection(const QString& flightID)
716
{
717 718 719 720 721 722 723 724 725 726 727 728 729 730 731
    _flightID = flightID;
    auto handler = [this](const Traffic::Monitor::Result& result) {
        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 {
            try {
                std::rethrow_exception(result.error());
            } catch (const std::exception& e) {
                // TODO: error
            }
        }
    };
732

733 734
    Traffic::Monitor::Params params{flightID.toStdString(), _shared.loginToken().toStdString()};
    _shared.client()->traffic().monitor(params, handler);
735 736
}

737
void AirMapTrafficMonitor::_update(Traffic::Update::Type type, const std::vector<Traffic::Update>& update)
738
{
739
    qCDebug(AirMapManagerLog) << "Traffic update with" << update.size() << "elements";
740

741 742
    if (type != Traffic::Update::Type::situational_awareness)
        return; // currently we're only interested in situational awareness
743

744 745 746 747 748
    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);
749 750 751
    }
}

752 753 754 755 756 757 758 759
void AirMapTrafficMonitor::stop()
{
    if (_monitor) {
        _monitor->unsubscribe(_subscriber);
        _subscriber.reset();
        _monitor.reset();
    }
}
760

761
AirMapManagerPerVehicle::AirMapManagerPerVehicle(AirMapSharedState& shared, const Vehicle& vehicle,
762
        QGCToolbox& toolbox)
763 764
    : AirspaceManagerPerVehicle(vehicle), _shared(shared),
    _flightManager(shared), _telemetry(shared), _trafficMonitor(shared),
765
    _toolbox(toolbox)
766
{
767 768 769 770
    connect(&_flightManager, &AirMapFlightManager::flightPermitStatusChanged,
            this, &AirMapManagerPerVehicle::flightPermitStatusChanged);
    connect(&_flightManager, &AirMapFlightManager::flightPermitStatusChanged,
            this, &AirMapManagerPerVehicle::_flightPermitStatusChanged);
771 772 773
    //connect(&_flightManager, &AirMapFlightManager::networkError, this, &AirMapManagerPerVehicle::networkError);
    //connect(&_telemetry, &AirMapTelemetry::networkError, this, &AirMapManagerPerVehicle::networkError);
    connect(&_trafficMonitor, &AirMapTrafficMonitor::trafficUpdate, this, &AirspaceManagerPerVehicle::trafficUpdate);
774 775
}

776
void AirMapManagerPerVehicle::createFlight(const QList<MissionItem*>& missionItems)
777
{
778 779
    if (!_shared.client()) {
        qCDebug(AirMapManagerLog) << "No AirMap client instance. Will not create a flight";
780
        return;
781
    }
782 783
    _flightManager.createFlight(missionItems);
}
784

785 786 787
AirspaceAuthorization::PermitStatus AirMapManagerPerVehicle::flightPermitStatus() const
{
    return _flightManager.flightPermitStatus();
788 789
}

790
void AirMapManagerPerVehicle::startTelemetryStream()
791
{
792 793 794 795
    if (_flightManager.flightID() != "") {
        _telemetry.startTelemetryStream(_flightManager.flightID());
    }
}
796

797 798 799
void AirMapManagerPerVehicle::stopTelemetryStream()
{
    _telemetry.stopTelemetryStream();
800 801
}

802
bool AirMapManagerPerVehicle::isTelemetryStreaming() const
803
{
804
    return _telemetry.isTelemetryStreaming();
805 806
}

807
void AirMapManagerPerVehicle::endFlight()
808
{
809
    _flightManager.endFlight();
810
    _trafficMonitor.stop();
811
}
812

813 814 815 816
void AirMapManagerPerVehicle::vehicleMavlinkMessageReceived(const mavlink_message_t& message)
{
    if (isTelemetryStreaming()) {
        _telemetry.vehicleMavlinkMessageReceived(message);
817 818 819
    }
}

820
void AirMapManagerPerVehicle::_flightPermitStatusChanged()
821
{
822 823 824 825
    // 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
826
        _trafficMonitor.startConnection(_flightManager.flightID());
827 828 829
    }
}

830 831 832
AirMapManager::AirMapManager(QGCApplication* app, QGCToolbox* toolbox)
    : AirspaceManager(app, toolbox)
{
833 834 835 836 837 838 839 840 841 842 843 844 845 846 847
    _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();
    }
848 849
}

850 851
void AirMapManager::setToolbox(QGCToolbox* toolbox)
{
852
    AirspaceManager::setToolbox(toolbox);
853
    AirMapSettings* ap = toolbox->settingsManager()->airMapSettings();
854 855 856 857 858 859 860 861

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

    connect(ap->sitaUserReg(),   &Fact::rawValueChanged, this, &AirMapManager::_settingsChanged);
    connect(ap->sitaUavReg(),   &Fact::rawValueChanged, this, &AirMapManager::_settingsChanged);
862 863 864 865 866 867 868 869 870 871

    _settingsChanged();

}

void AirMapManager::_error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails)
{
    //TODO: console message & UI message
    //qgcApp()->showMessage(QString("AirMap error: %1%2").arg(errorString).arg(errorDetails));
    qCDebug(AirMapManagerLog) << "Caught error: "<<what<<", "<<airmapdMessage<<", "<<airmapdDetails;
872 873 874 875 876 877 878
}

void AirMapManager::_settingsChanged()
{
    qCDebug(AirMapManagerLog) << "AirMap settings changed";

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

880 881 882 883 884 885 886
    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);
887

888 889 890 891
    // need to re-create the client if the API key changed
    if (_shared.client() && apiKeyChanged) {
        delete _shared.client();
        _shared.setClient(nullptr);
892
    }
893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910


    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");
                // TODO: user error message
            }
        });
911 912 913
    }
}

914
AirspaceManagerPerVehicle* AirMapManager::instantiateVehicle(const Vehicle& vehicle)
915
{
916 917
    AirMapManagerPerVehicle* manager = new AirMapManagerPerVehicle(_shared, vehicle, *_toolbox);
    //connect(manager, &AirMapManagerPerVehicle::networkError, this, &AirMapManager::_networkError);
918
    return manager;
919 920
}

921
AirspaceRestrictionProvider* AirMapManager::instantiateRestrictionProvider()
922
{
923 924 925
    AirMapRestrictionManager* restrictionManager = new AirMapRestrictionManager(_shared);
    //connect(restrictionManager, &AirMapRestrictionManager::networkError, this, &AirMapManager::_networkError);
    connect(restrictionManager, &AirMapRestrictionManager::error, this, &AirMapManager::_error);
926
    return restrictionManager;
927 928
}