Browse Source

WIP (not done and not working)

Break apart string of classes into their own files as all in one file became unwieldy
Expose Airspace data in a QML ready format
Split global Airspace from AirMap (Only now I figured out the reason for the pure virtual root classes)
Refactored a bunch of things to make it consistent and/or obvious
QGC4.4
Gus Grubba 7 years ago
parent
commit
6b47e10767
  1. 46
      qgroundcontrol.pro
  2. 384
      src/Airmap/AirMapFlightManager.cc
  3. 98
      src/Airmap/AirMapFlightManager.h
  4. 973
      src/Airmap/AirMapManager.cc
  5. 348
      src/Airmap/AirMapManager.h
  6. 92
      src/Airmap/AirMapRestrictionManager.cc
  7. 39
      src/Airmap/AirMapRestrictionManager.h
  8. 66
      src/Airmap/AirMapRulesetsManager.cc
  9. 42
      src/Airmap/AirMapRulesetsManager.h
  10. 94
      src/Airmap/AirMapSharedState.cc
  11. 68
      src/Airmap/AirMapSharedState.h
  12. 135
      src/Airmap/AirMapTelemetry.cc
  13. 58
      src/Airmap/AirMapTelemetry.h
  14. 53
      src/Airmap/AirMapTrafficMonitor.cc
  15. 47
      src/Airmap/AirMapTrafficMonitor.h
  16. 84
      src/Airmap/AirMapVehicleManager.cc
  17. 56
      src/Airmap/AirMapVehicleManager.h
  18. 65
      src/Airmap/AirmapWeatherInformation.cc
  19. 58
      src/Airmap/AirmapWeatherInformation.h
  20. 55
      src/Airmap/AirspaceController.h
  21. 278
      src/Airmap/AirspaceManagement.h
  22. 23
      src/AirspaceManagement/AirspaceController.cc
  23. 37
      src/AirspaceManagement/AirspaceController.h
  24. 114
      src/AirspaceManagement/AirspaceManagement.cc
  25. 138
      src/AirspaceManagement/AirspaceManagement.h
  26. 31
      src/AirspaceManagement/AirspaceRestriction.cc
  27. 64
      src/AirspaceManagement/AirspaceRestriction.h
  28. 15
      src/AirspaceManagement/AirspaceRestrictionProvider.cc
  29. 42
      src/AirspaceManagement/AirspaceRestrictionProvider.h
  30. 15
      src/AirspaceManagement/AirspaceRulesetsProvider.cc
  31. 34
      src/AirspaceManagement/AirspaceRulesetsProvider.h
  32. 42
      src/AirspaceManagement/AirspaceVehicleManager.cc
  33. 64
      src/AirspaceManagement/AirspaceVehicleManager.h
  34. 15
      src/AirspaceManagement/AirspaceWeatherInfoProvider.cc
  35. 56
      src/AirspaceManagement/AirspaceWeatherInfoProvider.h
  36. 2
      src/MissionManager/PlanManager.cc
  37. 4
      src/QGCApplication.cc
  38. 3
      src/QGCToolbox.cc
  39. 4
      src/Vehicle/Vehicle.cc
  40. 4
      src/Vehicle/Vehicle.h

46
qgroundcontrol.pro

@ -1058,6 +1058,30 @@ SOURCES += \ @@ -1058,6 +1058,30 @@ SOURCES += \
# AirMap
contains (DEFINES, QGC_AIRMAP_ENABLED) {
#-- These should be always enabled but not yet
INCLUDEPATH += \
src/AirspaceManagement
HEADERS += \
src/AirspaceManagement/AirspaceController.h \
src/AirspaceManagement/AirspaceManagement.h \
src/AirspaceManagement/AirspaceRestriction.h \
src/AirspaceManagement/AirspaceRestrictionProvider.h \
src/AirspaceManagement/AirspaceRulesetsProvider.h \
src/AirspaceManagement/AirspaceWeatherInfoProvider.h \
src/AirspaceManagement/AirspaceVehicleManager.h \
SOURCES += \
src/AirspaceManagement/AirspaceController.cc \
src/AirspaceManagement/AirspaceManagement.cc \
src/AirspaceManagement/AirspaceRestriction.cc \
src/AirspaceManagement/AirspaceRestrictionProvider.cc \
src/AirspaceManagement/AirspaceRulesetsProvider.cc \
src/AirspaceManagement/AirspaceWeatherInfoProvider.cc \
src/AirspaceManagement/AirspaceVehicleManager.cc \
#-- This is the AirMap implementation of the above
RESOURCES += \
src/Airmap/airmap.qrc
@ -1065,16 +1089,32 @@ contains (DEFINES, QGC_AIRMAP_ENABLED) { @@ -1065,16 +1089,32 @@ contains (DEFINES, QGC_AIRMAP_ENABLED) {
src/Airmap
HEADERS += \
src/Airmap/AirspaceController.h \
src/Airmap/AirMapManager.h \
src/Airmap/AirspaceManagement.h \
src/Airmap/AirMapSettings.h
src/Airmap/AirMapSettings.h \
src/Airmap/AirmapWeatherInformation.h \
src/Airmap/AirMapRestrictionManager.h \
src/Airmap/AirMapRulesetsManager.h \
src/Airmap/AirMapSharedState.h \
src/Airmap/AirMapFlightManager.h \
src/Airmap/AirMapTelemetry.h \
src/Airmap/AirMapTrafficMonitor.h \
src/Airmap/AirMapVehicleManager.h \
SOURCES += \
src/Airmap/AirMapManager.cc \
src/Airmap/AirspaceManagement.cc \
src/Airmap/AirspaceController.cc \
src/Airmap/AirMapSettings.cc
src/Airmap/AirMapSettings.cc \
src/Airmap/AirmapWeatherInformation.cc \
src/Airmap/AirMapRestrictionManager.cc \
src/Airmap/AirMapRulesetsManager.cc \
src/Airmap/AirMapSharedState.cc \
src/Airmap/AirMapFlightManager.cc \
src/Airmap/AirMapTelemetry.cc \
src/Airmap/AirMapTrafficMonitor.cc \
src/Airmap/AirMapVehicleManager.cc \
} else {
RESOURCES += \
src/Airmap/dummy/airmap_dummy.qrc

384
src/Airmap/AirMapFlightManager.cc

@ -0,0 +1,384 @@ @@ -0,0 +1,384 @@
#include "AirMapFlightManager.h"
AirMapFlightManager::AirMapFlightManager(AirMapSharedState& shared)
: _shared(shared)
{
connect(&_pollTimer, &QTimer::timeout, this, &AirMapFlightManager::_pollBriefing);
}
void AirMapFlightManager::createFlight(const QList<MissionItem*>& missionItems)
{
if (!_shared.client()) {
qCDebug(AirMapManagerLog) << "No AirMap client instance. Will not create a flight";
return;
}
if (_state != State::Idle) {
qCWarning(AirMapManagerLog) << "AirMapFlightManager::createFlight: State not idle";
return;
}
_flight.reset();
// 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.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();
}
}
break;
default:
break;
}
}
if (_flight.coords.empty()) {
return;
}
_flight.maxAltitude += 5; // add a safety buffer
if (_pilotID == "") {
// need to get the pilot id before uploading the flight
qCDebug(AirMapManagerLog) << "Getting pilot ID";
_state = State::GetPilotID;
std::weak_ptr<LifetimeChecker> isAlive(_instance);
_shared.doRequestWithLogin([this, isAlive](const QString& login_token) {
if (!isAlive.lock()) return;
Pilots::Authenticated::Parameters params;
params.authorization = login_token.toStdString();
_shared.client()->pilots().authenticated(params, [this, isAlive](const Pilots::Authenticated::Result& result) {
if (!isAlive.lock()) return;
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;
QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
emit error("Failed to create Flight Plan",
QString::fromStdString(result.error().message()), description);
}
});
});
} else {
_uploadFlight();
}
_flightPermitStatus = AirspaceAuthorization::PermitPending;
emit flightPermitStatusChanged();
}
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};
std::weak_ptr<LifetimeChecker> isAlive(_instance);
_shared.client()->flights().search(params, [this, isAlive](const Flights::Search::Result& result) {
if (!isAlive.lock()) return;
if (_state != State::EndFirstFlight) return;
if (result && result.value().flights.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().flights[0].id; // pick the first flight (TODO: match the vehicle id)
_shared.client()->flights().end_flight(params, [this, isAlive](const Flights::EndFlight::Result& result) {
if (!isAlive.lock()) return;
if (_state != State::EndFirstFlight) return;
if (!result) {
QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
emit error("Failed to end first Flight",
QString::fromStdString(result.error().message()), description);
}
_state = State::Idle;
_uploadFlight();
});
} else {
_state = State::Idle;
_uploadFlight();
}
});
}
void AirMapFlightManager::_uploadFlight()
{
if (_pendingFlightId != "") {
// we need to end an existing flight first
_endFlight(_pendingFlightId);
return;
}
if (_noFlightCreatedYet) {
_endFirstFlight();
_noFlightCreatedYet = false;
return;
}
qCDebug(AirMapManagerLog) << "uploading flight";
_state = State::FlightUpload;
std::weak_ptr<LifetimeChecker> isAlive(_instance);
_shared.doRequestWithLogin([this, isAlive](const QString& login_token) {
if (!isAlive.lock()) return;
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);
}
params.geometry = Geometry(lineString);
params.authorization = login_token.toStdString();
_flight.coords.clear();
_shared.client()->flight_plans().create_by_polygon(params, [this, isAlive](const FlightPlans::Create::Result& result) {
if (!isAlive.lock()) return;
if (_state != State::FlightUpload) return;
if (result) {
_pendingFlightPlan = QString::fromStdString(result.value().id);
qCDebug(AirMapManagerLog) << "Flight Plan created:"<<_pendingFlightPlan;
_checkForValidBriefing();
} else {
QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
emit error("Flight Plan creation failed",
QString::fromStdString(result.error().message()), description);
}
});
});
}
void AirMapFlightManager::_checkForValidBriefing()
{
_state = State::FlightBrief;
FlightPlans::RenderBriefing::Parameters params;
params.authorization = _shared.loginToken().toStdString();
params.id = _pendingFlightPlan.toStdString();
std::weak_ptr<LifetimeChecker> isAlive(_instance);
_shared.client()->flight_plans().render_briefing(params, [this, isAlive](const FlightPlans::RenderBriefing::Result& result) {
if (!isAlive.lock()) return;
if (_state != State::FlightBrief) return;
if (result) {
bool allValid = true;
for (const auto& validation : result.value().evaluation.validations) {
if (validation.status != Evaluation::Validation::Status::valid) {
emit error(QString("%1 registration identifier is invalid: %2").arg(
QString::fromStdString(validation.authority.name)).arg(QString::fromStdString(validation.message)), "", "");
allValid = false;
}
}
if (allValid) {
_submitPendingFlightPlan();
} else {
_flightPermitStatus = AirspaceAuthorization::PermitRejected;
emit flightPermitStatusChanged();
_state = State::Idle;
}
} else {
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;
}
});
}
void AirMapFlightManager::_submitPendingFlightPlan()
{
_state = State::FlightSubmit;
FlightPlans::Submit::Parameters params;
params.authorization = _shared.loginToken().toStdString();
params.id = _pendingFlightPlan.toStdString();
std::weak_ptr<LifetimeChecker> isAlive(_instance);
_shared.client()->flight_plans().submit(params, [this, isAlive](const FlightPlans::Submit::Result& result) {
if (!isAlive.lock()) return;
if (_state != State::FlightSubmit) return;
if (result) {
_pendingFlightId = QString::fromStdString(result.value().flight_id.get());
_state = State::FlightPolling;
_pollBriefing();
} else {
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;
}
});
}
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();
std::weak_ptr<LifetimeChecker> isAlive(_instance);
_shared.client()->flight_plans().render_briefing(params, [this, isAlive](const FlightPlans::RenderBriefing::Result& result) {
if (!isAlive.lock()) return;
if (_state != State::FlightPolling) return;
if (result) {
const FlightPlan::Briefing& briefing = result.value();
qCDebug(AirMapManagerLog) << "flight polling/briefing response";
bool rejected = false;
bool accepted = false;
bool pending = false;
for (const auto& authorization : briefing.evaluation.authorizations) {
switch (authorization.status) {
case Evaluation::Authorization::Status::accepted:
case Evaluation::Authorization::Status::accepted_upon_submission:
accepted = true;
break;
case Evaluation::Authorization::Status::rejected:
case Evaluation::Authorization::Status::rejected_upon_submission:
rejected = true;
break;
case Evaluation::Authorization::Status::pending:
pending = true;
break;
}
}
if (briefing.evaluation.authorizations.size() == 0) {
// if we don't get any authorizations, we assume it's accepted
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);
}
} else {
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;
}
});
}
void AirMapFlightManager::endFlight()
{
if (_currentFlightId.length() == 0) {
return;
}
if (_state != State::Idle) {
qCWarning(AirMapManagerLog) << "AirMapFlightManager::endFlight: State not idle";
return;
}
_endFlight(_currentFlightId);
_flightPermitStatus = AirspaceAuthorization::PermitUnknown;
emit flightPermitStatusChanged();
}
void AirMapFlightManager::_endFlight(const QString& flightID)
{
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();
std::weak_ptr<LifetimeChecker> isAlive(_instance);
_shared.client()->flights().end_flight(params, [this, isAlive](const Flights::EndFlight::Result& result) {
if (!isAlive.lock()) return;
if (_state != State::FlightEnd) return;
_state = State::Idle;
_pendingFlightId = "";
_pendingFlightPlan = "";
_currentFlightId = "";
if (result) {
if (!_flight.coords.empty()) {
_uploadFlight();
}
} else {
QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
emit error("Failed to end Flight",
QString::fromStdString(result.error().message()), description);
}
});
}

98
src/Airmap/AirMapFlightManager.h

@ -0,0 +1,98 @@ @@ -0,0 +1,98 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include <QObject>
#include <QTimer>
#include "AirMapManager.h"
//-----------------------------------------------------------------------------
/// class to upload a flight
class AirMapFlightManager : public QObject, public LifetimeChecker
{
Q_OBJECT
public:
AirMapFlightManager(AirMapSharedState& shared);
/// Send flight path to AirMap
void createFlight(const QList<MissionItem*>& missionItems);
AirspaceAuthorization::PermitStatus flightPermitStatus() const { return _flightPermitStatus; }
const QString& flightID() const { return _currentFlightId; }
public slots:
void endFlight();
signals:
void error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
void flightPermitStatusChanged();
private slots:
void _pollBriefing();
private:
/**
* upload flight stored in _flight
*/
void _uploadFlight();
/**
* query the active flights and end the first one (because only a single flight can be active at a time).
*/
void _endFirstFlight();
/**
* implementation of endFlight()
*/
void _endFlight(const QString& flightID);
/**
* check if the briefing response is valid and call _submitPendingFlightPlan() if it is.
*/
void _checkForValidBriefing();
void _submitPendingFlightPlan();
enum class State {
Idle,
GetPilotID,
FlightUpload,
FlightBrief,
FlightSubmit,
FlightPolling, // poll & check for approval
FlightEnd,
EndFirstFlight, // get a list of open flights & end the first one (because there can only be 1 active at a time)
};
struct Flight {
QList<QGeoCoordinate> coords;
QGeoCoordinate takeoffCoord;
float maxAltitude = 0;
void reset() {
coords.clear();
maxAltitude = 0;
}
};
Flight _flight; ///< flight pending to be uploaded
State _state = State::Idle;
AirMapSharedState& _shared;
QString _currentFlightId; ///< Flight ID, empty if there is none
QString _pendingFlightId; ///< current flight ID, not necessarily accepted yet (once accepted, it's equal to _currentFlightId)
QString _pendingFlightPlan; ///< current flight plan, waiting to be submitted
AirspaceAuthorization::PermitStatus _flightPermitStatus = AirspaceAuthorization::PermitUnknown;
QString _pilotID; ///< Pilot ID in the form "auth0|abc123"
bool _noFlightCreatedYet = true;
QTimer _pollTimer; ///< timer to poll for approval check
};

973
src/Airmap/AirMapManager.cc

File diff suppressed because it is too large Load Diff

348
src/Airmap/AirMapManager.h

@ -11,27 +11,16 @@ @@ -11,27 +11,16 @@
#include "QGCToolbox.h"
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
#include "MissionItem.h"
#include "MultiVehicleManager.h"
#include "AirspaceManagement.h"
#include <QGeoCoordinate>
#include <QList>
#include <QQueue>
#include <QTimer>
#include <cstdint>
#include <functional>
#include <memory>
#include <airmap/qt/client.h>
#include <airmap/qt/logger.h>
#include <airmap/qt/types.h>
#include <airmap/traffic.h>
Q_DECLARE_LOGGING_CATEGORY(AirMapManagerLog)
class AirMapSharedState;
//-----------------------------------------------------------------------------
/**
* @class LifetimeChecker
* Base class which helps to check if an object instance still exists.
@ -48,311 +37,11 @@ protected: @@ -48,311 +37,11 @@ protected:
std::shared_ptr<LifetimeChecker> _instance;
};
//-----------------------------------------------------------------------------
/**
* @class AirMapSharedState
* contains state & settings that need to be shared (such as login)
* @class AirMapManager
* AirMap implementation of AirspaceManager
*/
class AirMapSharedState : public QObject
{
Q_OBJECT
public:
struct Settings {
QString apiKey;
// login credentials
QString clientID;
QString userName; ///< use anonymous login if empty
QString password;
};
void setSettings(const Settings& settings);
const Settings& settings() const { return _settings; }
void setClient(airmap::qt::Client* client) { _client = client; }
/**
* Get the current client instance. It can be NULL. If not NULL, it implies
* there's an API key set.
*/
airmap::qt::Client* client() const { return _client; }
bool hasAPIKey() const { return _settings.apiKey != ""; }
bool isLoggedIn() const { return _loginToken != ""; }
using Callback = std::function<void(const QString& /* login_token */)>;
/**
* Do a request that requires user login: if not yet logged in, the request is queued and
* processed after successful login, otherwise it's executed directly.
*/
void doRequestWithLogin(const Callback& callback);
void login();
void logout();
const QString& loginToken() const { return _loginToken; }
signals:
void error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
private:
void _processPendingRequests();
bool _isLoginInProgress = false;
QString _loginToken; ///< login token: empty when not logged in
airmap::qt::Client* _client = nullptr;
Settings _settings;
QQueue<Callback> _pendingRequests; ///< pending requests that are processed after a successful login
};
/// class to download polygons from AirMap
class AirMapRestrictionManager : public AirspaceRestrictionProvider, public LifetimeChecker
{
Q_OBJECT
public:
AirMapRestrictionManager(AirMapSharedState& shared);
void setROI(const QGeoCoordinate& center, double radiusMeters) override;
signals:
void error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
private:
static void _addPolygonToList(const airmap::Geometry::Polygon& polygon, QList<PolygonAirspaceRestriction*>& list);
enum class State {
Idle,
RetrieveItems,
};
State _state = State::Idle;
AirMapSharedState& _shared;
};
/// class to download rulesets from AirMap
class AirMapRulesetsManager : public AirspaceRulesetsProvider, public LifetimeChecker
{
Q_OBJECT
public:
AirMapRulesetsManager (AirMapSharedState& shared);
void setROI (const QGeoCoordinate& center) override;
signals:
void error (const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
private:
enum class State {
Idle,
RetrieveItems,
};
State _state = State::Idle;
AirMapSharedState& _shared;
};
/// class to upload a flight
class AirMapFlightManager : public QObject, public LifetimeChecker
{
Q_OBJECT
public:
AirMapFlightManager(AirMapSharedState& shared);
/// Send flight path to AirMap
void createFlight(const QList<MissionItem*>& missionItems);
AirspaceAuthorization::PermitStatus flightPermitStatus() const { return _flightPermitStatus; }
const QString& flightID() const { return _currentFlightId; }
public slots:
void endFlight();
signals:
void error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
void flightPermitStatusChanged();
private slots:
void _pollBriefing();
private:
/**
* upload flight stored in _flight
*/
void _uploadFlight();
/**
* query the active flights and end the first one (because only a single flight can be active at a time).
*/
void _endFirstFlight();
/**
* implementation of endFlight()
*/
void _endFlight(const QString& flightID);
/**
* check if the briefing response is valid and call _submitPendingFlightPlan() if it is.
*/
void _checkForValidBriefing();
void _submitPendingFlightPlan();
enum class State {
Idle,
GetPilotID,
FlightUpload,
FlightBrief,
FlightSubmit,
FlightPolling, // poll & check for approval
FlightEnd,
EndFirstFlight, // get a list of open flights & end the first one (because there can only be 1 active at a time)
};
struct Flight {
QList<QGeoCoordinate> coords;
QGeoCoordinate takeoffCoord;
float maxAltitude = 0;
void reset() {
coords.clear();
maxAltitude = 0;
}
};
Flight _flight; ///< flight pending to be uploaded
State _state = State::Idle;
AirMapSharedState& _shared;
QString _currentFlightId; ///< Flight ID, empty if there is none
QString _pendingFlightId; ///< current flight ID, not necessarily accepted yet (once accepted, it's equal to _currentFlightId)
QString _pendingFlightPlan; ///< current flight plan, waiting to be submitted
AirspaceAuthorization::PermitStatus _flightPermitStatus = AirspaceAuthorization::PermitUnknown;
QString _pilotID; ///< Pilot ID in the form "auth0|abc123"
bool _noFlightCreatedYet = true;
QTimer _pollTimer; ///< timer to poll for approval check
};
/// class to send telemetry data to AirMap
class AirMapTelemetry : public QObject, public LifetimeChecker
{
Q_OBJECT
public:
AirMapTelemetry(AirMapSharedState& shared);
virtual ~AirMapTelemetry() = default;
/**
* Setup the connection to start sending telemetry
*/
void startTelemetryStream(const QString& flightID);
void stopTelemetryStream();
bool isTelemetryStreaming() const;
signals:
void error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
public slots:
void vehicleMavlinkMessageReceived(const mavlink_message_t& message);
private:
void _handleGlobalPositionInt(const mavlink_message_t& message);
void _handleGPSRawInt(const mavlink_message_t& message);
enum class State {
Idle,
StartCommunication,
EndCommunication,
Streaming,
};
State _state = State::Idle;
AirMapSharedState& _shared;
std::string _key; ///< key for AES encryption (16 bytes)
QString _flightID;
float _lastHdop = 1.f;
};
class AirMapTrafficMonitor : public QObject, public LifetimeChecker
{
Q_OBJECT
public:
AirMapTrafficMonitor(AirMapSharedState& shared)
: _shared(shared)
{
}
virtual ~AirMapTrafficMonitor();
void startConnection(const QString& flightID);
void stop();
signals:
void error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
void trafficUpdate(QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading);
private:
void _update(airmap::Traffic::Update::Type type, const std::vector<airmap::Traffic::Update>& update);
private:
QString _flightID;
AirMapSharedState& _shared;
std::shared_ptr<airmap::Traffic::Monitor> _monitor;
std::shared_ptr<airmap::Traffic::Monitor::Subscriber> _subscriber;
};
/// AirMap per vehicle management class.
class AirMapManagerPerVehicle : public AirspaceManagerPerVehicle
{
Q_OBJECT
public:
AirMapManagerPerVehicle(AirMapSharedState& shared, const Vehicle& vehicle, QGCToolbox& toolbox);
virtual ~AirMapManagerPerVehicle() = default;
void createFlight(const QList<MissionItem*>& missionItems) override;
AirspaceAuthorization::PermitStatus flightPermitStatus() const override;
void startTelemetryStream() override;
void stopTelemetryStream() override;
bool isTelemetryStreaming() const override;
signals:
void error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
public slots:
void endFlight() override;
protected slots:
virtual void vehicleMavlinkMessageReceived(const mavlink_message_t& message) override;
private slots:
void _flightPermitStatusChanged();
private:
AirMapSharedState& _shared;
AirMapFlightManager _flightManager;
AirMapTelemetry _telemetry;
AirMapTrafficMonitor _trafficMonitor;
QGCToolbox& _toolbox;
};
class AirMapManager : public AirspaceManager
{
@ -362,26 +51,23 @@ public: @@ -362,26 +51,23 @@ public:
AirMapManager(QGCApplication* app, QGCToolbox* toolbox);
virtual ~AirMapManager();
void setToolbox(QGCToolbox* toolbox) override;
void setToolbox (QGCToolbox* toolbox) override;
AirspaceManagerPerVehicle* instantiateVehicle (const Vehicle& vehicle) override;
AirspaceRestrictionProvider* instantiateRestrictionProvider () override;
AirspaceRulesetsProvider* instantiateRulesetsProvider () override;
AirspaceVehicleManager* instantiateVehicle (const Vehicle& vehicle) override;
AirspaceRestrictionProvider* instantiateRestrictionProvider () override;
AirspaceRulesetsProvider* instantiateRulesetsProvider () override;
AirspaceWeatherInfoProvider* instatiateAirspaceWeatherInfoProvider () override;
QString name() const override { return "AirMap"; }
void requestWeatherUpdate(const QGeoCoordinate& coordinate) override;
QString name () const override { return "AirMap"; }
private slots:
void _error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
void _error (const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
void _settingsChanged ();
void _settingsChanged();
private:
AirMapSharedState _shared;
std::shared_ptr<airmap::qt::Logger> _logger;
std::shared_ptr<airmap::qt::DispatchingLogger> _dispatchingLogger;
AirMapSharedState _shared;
std::shared_ptr<airmap::qt::Logger> _logger;
std::shared_ptr<airmap::qt::DispatchingLogger> _dispatchingLogger;
};

92
src/Airmap/AirMapRestrictionManager.cc

@ -0,0 +1,92 @@ @@ -0,0 +1,92 @@
#include "AirMapRestrictionManager.h"
AirMapRestrictionManager::AirMapRestrictionManager(AirMapSharedState& shared)
: _shared(shared)
{
}
void
AirMapRestrictionManager::setROI(const QGeoCoordinate& center, double radiusMeters)
{
if (!_shared.client()) {
qCDebug(AirMapManagerLog) << "No AirMap client instance. Not updating Airspace";
return;
}
if (_state != State::Idle) {
qCWarning(AirMapManagerLog) << "AirMapRestrictionManager::updateROI: state not idle";
return;
}
qCDebug(AirMapManagerLog) << "setting ROI";
_polygonList.clear();
_circleList.clear();
_state = State::RetrieveItems;
Airspaces::Search::Parameters params;
params.geometry = Geometry::point(center.latitude(), center.longitude());
params.buffer = radiusMeters;
params.full = true;
std::weak_ptr<LifetimeChecker> isAlive(_instance);
_shared.client()->airspaces().search(params,
[this, isAlive](const Airspaces::Search::Result& result) {
if (!isAlive.lock()) return;
if (_state != State::RetrieveItems) return;
if (result) {
const std::vector<Airspace>& airspaces = result.value();
qCDebug(AirMapManagerLog)<<"Successful search. Items:" << 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();
_addPolygonToList(polygon, _polygonList);
}
break;
case Geometry::Type::multi_polygon: {
const Geometry::MultiPolygon& multiPolygon = geometry.details_for_multi_polygon();
for (const auto& polygon : multiPolygon) {
_addPolygonToList(polygon, _polygonList);
}
}
break;
case Geometry::Type::point: {
const Geometry::Point& point = geometry.details_for_point();
_circleList.append(new AirspaceCircularRestriction(QGeoCoordinate(point.latitude, point.longitude), 0.));
// TODO: radius???
}
break;
default:
qWarning() << "unsupported geometry type: "<<(int)geometry.type();
break;
}
}
} else {
QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
emit error("Failed to retrieve Geofences",
QString::fromStdString(result.error().message()), description);
}
emit requestDone(true);
_state = State::Idle;
});
}
void
AirMapRestrictionManager::_addPolygonToList(const airmap::Geometry::Polygon& polygon, QList<AirspacePolygonRestriction*>& list)
{
QVariantList polygonArray;
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);
}
polygonArray.append(QVariant::fromValue(coord));
}
list.append(new AirspacePolygonRestriction(polygonArray));
if (polygon.inner_rings.size() > 0) {
// no need to support those (they are rare, and in most cases, there's a more restrictive polygon filling the hole)
qCDebug(AirMapManagerLog) << "Polygon with holes. Size: "<<polygon.inner_rings.size();
}
}

39
src/Airmap/AirMapRestrictionManager.h

@ -0,0 +1,39 @@ @@ -0,0 +1,39 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include <QObject>
#include "AirspaceRestrictionProvider.h"
/**
* @file AirMapRestrictionManager.h
* Class to download polygons from AirMap
*/
class AirMapRestrictionManager : public AirspaceRestrictionProvider, public LifetimeChecker
{
Q_OBJECT
public:
AirMapRestrictionManager (AirMapSharedState& shared);
void setROI (const QGeoCoordinate& center, double radiusMeters) override;
signals:
void error (const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
private:
static void _addPolygonToList (const airmap::Geometry::Polygon& polygon, QList<AirspacePolygonRestriction*>& list);
enum class State {
Idle,
RetrieveItems,
};
State _state = State::Idle;
AirMapSharedState& _shared;
};

66
src/Airmap/AirMapRulesetsManager.cc

@ -0,0 +1,66 @@ @@ -0,0 +1,66 @@
#include "AirMapRulesetsManager.h"
//-----------------------------------------------------------------------------
AirMapRulesetsManager::AirMapRulesetsManager(AirMapSharedState& shared)
: _shared(shared)
{
}
//-----------------------------------------------------------------------------
void AirMapRulesetsManager::setROI(const QGeoCoordinate& center)
{
if (!_shared.client()) {
qCDebug(AirMapManagerLog) << "No AirMap client instance. Not updating Airspace";
return;
}
if (_state != State::Idle) {
qCWarning(AirMapManagerLog) << "AirMapRestrictionManager::updateROI: state not idle";
return;
}
qCDebug(AirMapManagerLog) << "Setting ROI for Rulesets";
_state = State::RetrieveItems;
RuleSets::Search::Parameters params;
params.geometry = Geometry::point(center.latitude(), center.longitude());
std::weak_ptr<LifetimeChecker> isAlive(_instance);
_shared.client()->rulesets().search(params,
[this, isAlive](const RuleSets::Search::Result& result) {
if (!isAlive.lock()) return;
if (_state != State::RetrieveItems) return;
if (result) {
const std::vector<RuleSet>& rulesets = result.value();
qCDebug(AirMapManagerLog)<<"Successful rulesets search. Items:" << rulesets.size();
for (const auto& ruleset : rulesets) {
qDebug() << "------------------------------------------";
qDebug() << "Jurisdiction:" << ruleset.jurisdiction.name.data() << (int)ruleset.jurisdiction.region;
qDebug() << "Name: " << ruleset.name.data();
qDebug() << "Short Name: " << ruleset.short_name.data();
qDebug() << "Description: " << ruleset.description.data();
qDebug() << "Is default: " << ruleset.is_default;
qDebug() << "Applicable to these airspace types:";
for (const auto& airspaceType : ruleset.airspace_types) {
qDebug() << airspaceType.data();
}
qDebug() << "Rules:";
for (const auto& rule : ruleset.rules) {
qDebug() << " --------------------------------------";
qDebug() << " " << rule.short_text.data();
qDebug() << " " << rule.description.data();
qDebug() << " " << rule.display_order;
qDebug() << " " << (int)rule.status;
qDebug() << " Features:";
for (const auto& feature : rule.features) {
qDebug() << " " << feature.name.data();
qDebug() << " " << feature.description.data();
qDebug() << " " << (int)feature.status;
}
}
}
} else {
QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
emit error("Failed to retrieve RuleSets",
QString::fromStdString(result.error().message()), description);
}
emit requestDone(true);
_state = State::Idle;
});
}

42
src/Airmap/AirMapRulesetsManager.h

@ -0,0 +1,42 @@ @@ -0,0 +1,42 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
/**
* @file AirMapRulesetsManager.h
* Class to download rulesets from AirMap
*/
#include <QObject>
#include "AirMapManager.h"
#include "AirspaceRulesetsProvider.h"
#include "AirMapSharedState.h"
class AirMapRulesetsManager : public AirspaceRulesetsProvider, public LifetimeChecker
{
Q_OBJECT
public:
AirMapRulesetsManager (AirMapSharedState& shared);
void setROI (const QGeoCoordinate& center) override;
signals:
void error (const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
private:
enum class State {
Idle,
RetrieveItems,
};
State _state = State::Idle;
AirMapSharedState& _shared;
};

94
src/Airmap/AirMapSharedState.cc

@ -0,0 +1,94 @@ @@ -0,0 +1,94 @@
#include "AirMapSharedState.h"
void
AirMapSharedState::setSettings(const Settings& settings)
{
logout();
_settings = settings;
}
void
AirMapSharedState::doRequestWithLogin(const Callback& callback)
{
if (isLoggedIn()) {
callback(_loginToken);
} else {
login();
_pendingRequests.enqueue(callback);
}
}
void
AirMapSharedState::login()
{
if (isLoggedIn() || _isLoginInProgress) {
return;
}
_isLoginInProgress = true;
if (_settings.userName == "") { //use anonymous login
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();
QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
emit error("Failed to authenticate with AirMap",
QString::fromStdString(result.error().message()), description);
}
});
} else {
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();
QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
emit error("Failed to authenticate with AirMap",
QString::fromStdString(result.error().message()), description);
}
});
}
}
void
AirMapSharedState::_processPendingRequests()
{
while (!_pendingRequests.isEmpty()) {
_pendingRequests.dequeue()(_loginToken);
}
}
void
AirMapSharedState::logout()
{
_isLoginInProgress = false; // cancel if we're currently trying to login
if (!isLoggedIn()) {
return;
}
_loginToken = "";
_pendingRequests.clear();
}

68
src/Airmap/AirMapSharedState.h

@ -0,0 +1,68 @@ @@ -0,0 +1,68 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include <QObject>
#include <airmap/qt/client.h>
/**
* @class AirMapSharedState
* Contains state & settings that need to be shared (such as login)
*/
class AirMapSharedState : public QObject
{
Q_OBJECT
public:
struct Settings {
QString apiKey;
// login credentials
QString clientID;
QString userName; ///< use anonymous login if empty
QString password;
};
void setSettings (const Settings& settings);
const Settings& settings () const { return _settings; }
void setClient (airmap::qt::Client* client) { _client = client; }
/**
* Get the current client instance. It can be NULL. If not NULL, it implies
* there's an API key set.
*/
airmap::qt::Client* client () const { return _client; }
bool hasAPIKey () const { return _settings.apiKey != ""; }
bool isLoggedIn () const { return _loginToken != ""; }
using Callback = std::function<void(const QString& /* login_token */)>;
/**
* Do a request that requires user login: if not yet logged in, the request is queued and
* processed after successful login, otherwise it's executed directly.
*/
void doRequestWithLogin (const Callback& callback);
void login ();
void logout ();
const QString& loginToken () const { return _loginToken; }
signals:
void error (const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
private:
void _processPendingRequests ();
private:
bool _isLoginInProgress = false;
QString _loginToken; ///< login token: empty when not logged in
airmap::qt::Client* _client = nullptr;
Settings _settings;
QQueue<Callback> _pendingRequests; ///< pending requests that are processed after a successful login
};

135
src/Airmap/AirMapTelemetry.cc

@ -0,0 +1,135 @@ @@ -0,0 +1,135 @@
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "AirMapTelemetry.h"
AirMapTelemetry::AirMapTelemetry(AirMapSharedState& shared)
: _shared(shared)
{
}
void AirMapTelemetry::vehicleMavlinkMessageReceived(const mavlink_message_t& message)
{
switch (message.msgid) {
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
_handleGlobalPositionInt(message);
break;
case MAVLINK_MSG_ID_GPS_RAW_INT:
_handleGPSRawInt(message);
break;
}
}
bool AirMapTelemetry::isTelemetryStreaming() const
{
return _state == State::Streaming;
}
void AirMapTelemetry::_handleGPSRawInt(const mavlink_message_t& message)
{
if (!isTelemetryStreaming()) {
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;
}
}
void AirMapTelemetry::_handleGlobalPositionInt(const mavlink_message_t& message)
{
if (!isTelemetryStreaming()) {
return;
}
mavlink_global_position_int_t globalPosition;
mavlink_msg_global_position_int_decode(&message, &globalPosition);
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
};
Flight flight;
flight.id = _flightID.toStdString();
_shared.client()->telemetry().submit_updates(flight, _key,
{Telemetry::Update{position}, Telemetry::Update{speed}});
}
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;
Flights::StartFlightCommunications::Parameters params;
params.authorization = _shared.loginToken().toStdString();
params.id = _flightID.toStdString();
std::weak_ptr<LifetimeChecker> isAlive(_instance);
_shared.client()->flights().start_flight_communications(params, [this, isAlive](const Flights::StartFlightCommunications::Result& result) {
if (!isAlive.lock()) return;
if (_state != State::StartCommunication) return;
if (result) {
_key = result.value().key;
_state = State::Streaming;
} else {
_state = State::Idle;
QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
emit error("Failed to start telemetry streaming",
QString::fromStdString(result.error().message()), description);
}
});
}
void AirMapTelemetry::stopTelemetryStream()
{
if (_state == State::Idle) {
return;
}
qCInfo(AirMapManagerLog) << "Stopping Telemetry stream with flightID" << _flightID;
_state = State::EndCommunication;
Flights::EndFlightCommunications::Parameters params;
params.authorization = _shared.loginToken().toStdString();
params.id = _flightID.toStdString();
std::weak_ptr<LifetimeChecker> isAlive(_instance);
_shared.client()->flights().end_flight_communications(params, [this, isAlive](const Flights::EndFlightCommunications::Result& result) {
Q_UNUSED(result);
if (!isAlive.lock()) return;
if (_state != State::EndCommunication) return;
_key = "";
_state = State::Idle;
});
}

58
src/Airmap/AirMapTelemetry.h

@ -0,0 +1,58 @@ @@ -0,0 +1,58 @@
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include <QObject>
#include "AirMapManager.h"
/// class to send telemetry data to AirMap
class AirMapTelemetry : public QObject, public LifetimeChecker
{
Q_OBJECT
public:
AirMapTelemetry(AirMapSharedState& shared);
virtual ~AirMapTelemetry() = default;
/**
* Setup the connection to start sending telemetry
*/
void startTelemetryStream(const QString& flightID);
void stopTelemetryStream();
bool isTelemetryStreaming() const;
signals:
void error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
public slots:
void vehicleMavlinkMessageReceived(const mavlink_message_t& message);
private:
void _handleGlobalPositionInt(const mavlink_message_t& message);
void _handleGPSRawInt(const mavlink_message_t& message);
enum class State {
Idle,
StartCommunication,
EndCommunication,
Streaming,
};
State _state = State::Idle;
AirMapSharedState& _shared;
std::string _key; ///< key for AES encryption (16 bytes)
QString _flightID;
float _lastHdop = 1.f;
};

53
src/Airmap/AirMapTrafficMonitor.cc

@ -0,0 +1,53 @@ @@ -0,0 +1,53 @@
#include "AirMapTrafficMonitor.h"
AirMapTrafficMonitor::~AirMapTrafficMonitor()
{
stop();
}
void
AirMapTrafficMonitor::startConnection(const QString& flightID)
{
_flightID = flightID;
std::weak_ptr<LifetimeChecker> isAlive(_instance);
auto handler = [this, isAlive](const Traffic::Monitor::Result& result) {
if (!isAlive.lock()) return;
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 {
QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
emit error("Failed to start Traffic Monitoring",
QString::fromStdString(result.error().message()), description);
}
};
Traffic::Monitor::Params params{flightID.toStdString(), _shared.loginToken().toStdString()};
_shared.client()->traffic().monitor(params, handler);
}
void
AirMapTrafficMonitor::_update(Traffic::Update::Type type, const std::vector<Traffic::Update>& update)
{
qCDebug(AirMapManagerLog) << "Traffic update with" << update.size() << "elements";
if (type != Traffic::Update::Type::situational_awareness)
return; // currently we're only interested in situational awareness
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);
}
}
void
AirMapTrafficMonitor::stop()
{
if (_monitor) {
_monitor->unsubscribe(_subscriber);
_subscriber.reset();
_monitor.reset();
}
}

47
src/Airmap/AirMapTrafficMonitor.h

@ -0,0 +1,47 @@ @@ -0,0 +1,47 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include <QObject>
/**
* @class AirMapTrafficMonitor
*
*/
class AirMapTrafficMonitor : public QObject, public LifetimeChecker
{
Q_OBJECT
public:
AirMapTrafficMonitor(AirMapSharedState& shared)
: _shared(shared)
{
}
virtual ~AirMapTrafficMonitor();
void startConnection(const QString& flightID);
void stop();
signals:
void error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
void trafficUpdate(QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading);
private:
void _update(airmap::Traffic::Update::Type type, const std::vector<airmap::Traffic::Update>& update);
private:
QString _flightID;
AirMapSharedState& _shared;
std::shared_ptr<airmap::Traffic::Monitor> _monitor;
std::shared_ptr<airmap::Traffic::Monitor::Subscriber> _subscriber;
};

84
src/Airmap/AirMapVehicleManager.cc

@ -0,0 +1,84 @@ @@ -0,0 +1,84 @@
#include "AirMapVehicleManager.h"
#include "AirMapFlightManager.h"
#include "AirMapTelemetry.h"
#include "AirMapTrafficMonitor.h"
AirMapVehicleManager::AirMapVehicleManager(AirMapSharedState& shared, const Vehicle& vehicle, QGCToolbox& toolbox)
: AirspaceVehicleManager(vehicle)
, _shared(shared)
, _flightManager(shared)
, _telemetry(shared)
, _trafficMonitor(shared)
, _toolbox(toolbox)
{
connect(&_flightManager, &AirMapFlightManager::flightPermitStatusChanged, this, &AirMapVehicleManager::flightPermitStatusChanged);
connect(&_flightManager, &AirMapFlightManager::flightPermitStatusChanged, this, &AirMapVehicleManager::_flightPermitStatusChanged);
connect(&_flightManager, &AirMapFlightManager::error, this, &AirMapVehicleManager::error);
connect(&_telemetry, &AirMapTelemetry::error, this, &AirMapVehicleManager::error);
connect(&_trafficMonitor, &AirMapTrafficMonitor::error, this, &AirMapVehicleManager::error);
connect(&_trafficMonitor, &AirMapTrafficMonitor::trafficUpdate, this, &AirspaceVehicleManager::trafficUpdate);
}
void
AirMapVehicleManager::createFlight(const QList<MissionItem*>& missionItems)
{
if (!_shared.client()) {
qCDebug(AirMapManagerLog) << "No AirMap client instance. Will not create a flight";
return;
}
_flightManager.createFlight(missionItems);
}
AirspaceAuthorization::PermitStatus
AirMapVehicleManager::flightPermitStatus() const
{
return _flightManager.flightPermitStatus();
}
void
AirMapVehicleManager::startTelemetryStream()
{
if (_flightManager.flightID() != "") {
_telemetry.startTelemetryStream(_flightManager.flightID());
}
}
void
AirMapVehicleManager::stopTelemetryStream()
{
_telemetry.stopTelemetryStream();
}
bool
AirMapVehicleManager::isTelemetryStreaming() const
{
return _telemetry.isTelemetryStreaming();
}
void
AirMapVehicleManager::endFlight()
{
_flightManager.endFlight();
_trafficMonitor.stop();
}
void
AirMapVehicleManager::vehicleMavlinkMessageReceived(const mavlink_message_t& message)
{
if (isTelemetryStreaming()) {
_telemetry.vehicleMavlinkMessageReceived(message);
}
}
void
AirMapVehicleManager::_flightPermitStatusChanged()
{
// 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
_trafficMonitor.startConnection(_flightManager.flightID());
}
}

56
src/Airmap/AirMapVehicleManager.h

@ -0,0 +1,56 @@ @@ -0,0 +1,56 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include <QObject>
#include "AirspaceManagement.h"
#include "AirspaceVehicleManager.h"
/// AirMap per vehicle management class.
class AirMapSharedState;
class AirMapFlightManager;
class AirMapTelemetry;
class AirMapTrafficMonitor;
class AirMapVehicleManager : public AirspaceVehicleManager
{
Q_OBJECT
public:
AirMapVehicleManager (AirMapSharedState& shared, const Vehicle& vehicle, QGCToolbox& toolbox);
~AirMapVehicleManager () = default;
void createFlight (const QList<MissionItem*>& missionItems) override;
void startTelemetryStream () override;
void stopTelemetryStream () override;
bool isTelemetryStreaming () const override;
AirspaceAuthorization::PermitStatus flightPermitStatus() const override;
signals:
void error (const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
public slots:
void endFlight () override;
protected slots:
virtual void vehicleMavlinkMessageReceived(const mavlink_message_t& message) override;
private slots:
void _flightPermitStatusChanged();
private:
AirMapSharedState& _shared;
AirMapFlightManager _flightManager;
AirMapTelemetry _telemetry;
AirMapTrafficMonitor _trafficMonitor;
QGCToolbox& _toolbox;
};

65
src/Airmap/AirmapWeatherInformation.cc

@ -0,0 +1,65 @@ @@ -0,0 +1,65 @@
#include "AirmapWeatherInformation.h"
AirMapWeatherInformation::AirMapWeatherInformation(AirMapSharedState& shared, QObject *parent)
: QObject(parent)
, _valid(false)
, _windHeading(0)
, _windSpeed(0)
, _windGusting(0)
, _temperature(0)
, _humidity(0.0f)
, _visibility(0)
, _precipitation(0)
{
}
void
AirMapWeatherInformation::setROI(QGeoCoordinate center)
{
//-- If first time or we've moved more than WEATHER_UPDATE_DISTANCE, ask for weather updates.
if(!_lastRoiCenter.isValid() || _lastRoiCenter.distanceTo(center) > WEATHER_UPDATE_DISTANCE) {
_lastRoiCenter = center;
_requestWeatherUpdate(center);
_weatherTime.start();
} else {
//-- Check weather once every WEATHER_UPDATE_TIME
if(_weatherTime.elapsed() > WEATHER_UPDATE_TIME) {
_requestWeatherUpdate(center);
_weatherTime.start();
}
}
}
void
AirMapWeatherInformation::_requestWeatherUpdate(const QGeoCoordinate& coordinate)
{
if (!_shared.client()) {
qCDebug(AirMapManagerLog) << "No AirMap client instance. Not updating Weather information";
_valid = false;
emit weatherChanged();
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;
AirMapWeatherInformation weatherUpdateInfo;
_valid = true;
_condition = QString::fromStdString(weather.condition);
_icon = QStringLiteral("qrc:/airmapweather/") + QString::fromStdString(weather.icon) + QStringLiteral(".svg");
_windHeading = weather.wind.heading;
_windSpeed = weather.wind.speed;
_windGusting = weather.wind.gusting;
_temperature = weather.temperature;
_humidity = weather.humidity;
_visibility = weather.visibility;
_precipitation = weather.precipitation;
} else {
_valid = false;
}
emit weatherChanged();
});
}

58
src/Airmap/AirmapWeatherInformation.h

@ -0,0 +1,58 @@ @@ -0,0 +1,58 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include <QObject>
#include <QGeoCoordinate>
#include "AirspaceWeatherInfoProvider.h"
/**
* @file AirMapWeatherInformation.h
* Weather information provided by AirMap.
*/
class AirMapWeatherInformation : public AirspaceWeatherInfoProvider, public LifetimeChecker
{
Q_OBJECT
friend class AirMapManager;
public:
AirMapWeatherInformation(AirMapSharedState &shared, QObject *parent = nullptr);
bool valid () override { return _valid; }
QString condition () override { return _condition; }
QString icon () override { return _icon; }
quint32 windHeading () override { return _windHeading; }
quint32 windSpeed () override { return _windSpeed; }
quint32 windGusting () override { return _windGusting; }
qint32 temperature () override { return _temperature; }
float humidity () override { return _humidity; }
quint32 visibility () override { return _visibility; }
quint32 precipitation () override { return _precipitation; }
void setROI (const QGeoCoordinate& center) override;
private:
void _requestWeatherUpdate (const QGeoCoordinate& coordinate);
private:
bool _valid;
QString _condition;
QString _icon;
quint32 _windHeading;
quint32 _windSpeed;
quint32 _windGusting;
qint32 _temperature;
float _humidity;
quint32 _visibility;
quint32 _precipitation;
//-- Don't check the weather every time the user moves the map
QGeoCoordinate _lastRoiCenter;
QTime _weatherTime;
};

55
src/Airmap/AirspaceController.h

@ -1,55 +0,0 @@ @@ -1,55 +0,0 @@
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "AirspaceManagement.h"
#include "QGCMapPolygon.h"
class AirspaceController : public QObject
{
Q_OBJECT
public:
AirspaceController(QObject* parent = NULL);
~AirspaceController() = default;
Q_PROPERTY(QmlObjectListModel* polygons READ polygons CONSTANT) ///< List of PolygonAirspaceRestriction objects
Q_PROPERTY(QmlObjectListModel* circles READ circles CONSTANT) ///< List of CircularAirspaceRestriction objects
Q_PROPERTY(QString weatherIcon READ weatherIcon NOTIFY weatherChanged)
Q_PROPERTY(int weatherTemp READ weatherTemp NOTIFY weatherChanged)
Q_PROPERTY(bool hasWeather READ hasWeather NOTIFY weatherChanged)
Q_INVOKABLE void setROI(QGeoCoordinate center, double radius);
QmlObjectListModel* polygons() { return _manager->polygonRestrictions(); }
QmlObjectListModel* circles() { return _manager->circularRestrictions(); }
Q_PROPERTY(QString providerName READ providerName CONSTANT)
QString providerName() { return _manager->name(); }
QString weatherIcon () { return _weatherIcon; }
int weatherTemp () { return _weatherTemp; }
bool hasWeather () { return _hasWeather; }
signals:
void weatherChanged ();
private slots:
void _weatherUpdate (bool success, QGeoCoordinate coordinate, WeatherInformation weather);
private:
AirspaceManager* _manager;
QGeoCoordinate _lastRoiCenter;
QTime _weatherTime;
QString _weatherIcon;
int _weatherTemp;
bool _hasWeather;
};

278
src/Airmap/AirspaceManagement.h

@ -1,278 +0,0 @@ @@ -1,278 +0,0 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
/**
* @file AirspaceManagement.h
* This file contains the interface definitions used by an airspace management implementation (AirMap).
* There are 3 base classes that must be subclassed:
* - AirspaceManager
* main manager that contains the restrictions for display. It acts as a factory to create instances of the other
* classes.
* - AirspaceManagerPerVehicle
* this provides the multi-vehicle support - each vehicle has an instance
* - AirspaceRestrictionProvider
* provides airspace restrictions. Currently only used by AirspaceManager, but
* each vehicle could have its own restrictions.
*/
#include "QGCToolbox.h"
#include "MissionItem.h"
#include <QObject>
#include <QString>
#include <QList>
#include <QGCLoggingCategory.h>
Q_DECLARE_LOGGING_CATEGORY(AirspaceManagementLog)
/**
* Contains the status of the Airspace authorization
*/
class AirspaceAuthorization : public QObject {
Q_OBJECT
public:
enum PermitStatus {
PermitUnknown = 0,
PermitPending,
PermitAccepted,
PermitRejected,
};
Q_ENUMS(PermitStatus);
};
/**
* Base class for an airspace restriction
*/
class AirspaceRestriction : public QObject
{
Q_OBJECT
public:
AirspaceRestriction(QObject* parent = NULL);
};
class PolygonAirspaceRestriction : public AirspaceRestriction
{
Q_OBJECT
public:
PolygonAirspaceRestriction(const QVariantList& polygon, QObject* parent = NULL);
Q_PROPERTY(QVariantList polygon MEMBER _polygon CONSTANT)
const QVariantList& getPolygon() const { return _polygon; }
private:
QVariantList _polygon;
};
class CircularAirspaceRestriction : public AirspaceRestriction
{
Q_OBJECT
public:
CircularAirspaceRestriction(const QGeoCoordinate& center, double radius, QObject* parent = NULL);
Q_PROPERTY(QGeoCoordinate center MEMBER _center CONSTANT)
Q_PROPERTY(double radius MEMBER _radius CONSTANT)
private:
QGeoCoordinate _center;
double _radius;
};
/**
* @class AirspaceRestrictionProvider
* Base class that queries for airspace restrictions
*/
class AirspaceRestrictionProvider : public QObject {
Q_OBJECT
public:
AirspaceRestrictionProvider() = default;
~AirspaceRestrictionProvider() = default;
/**
* Set region of interest that should be queried. When finished, the requestDone() signal will be emmited.
* @param center Center coordinate for ROI
* @param radiusMeters Radius in meters around center which is of interest
*/
virtual void setROI(const QGeoCoordinate& center, double radiusMeters) = 0;
const QList<PolygonAirspaceRestriction*>& polygons() const { return _polygonList; }
const QList<CircularAirspaceRestriction*>& circles() const { return _circleList; }
signals:
void requestDone(bool success);
protected:
QList<PolygonAirspaceRestriction*> _polygonList;
QList<CircularAirspaceRestriction*> _circleList;
};
/**
* @class AirspaceRulesetsProvider
* Base class that queries for airspace rulesets
*/
class AirspaceRulesetsProvider : public QObject {
Q_OBJECT
public:
AirspaceRulesetsProvider () = default;
~AirspaceRulesetsProvider () = default;
/**
* Set region of interest that should be queried. When finished, the requestDone() signal will be emmited.
* @param center Center coordinate for ROI
*/
virtual void setROI (const QGeoCoordinate& center) = 0;
signals:
void requestDone(bool success);
};
class AirspaceManagerPerVehicle;
class Vehicle;
struct WeatherInformation
{
QString condition; ///< The overall weather condition.
QString icon; ///< The icon or class of icon that should be used for display purposes.
uint32_t windHeading = 0; ///< The heading in [°].
uint32_t windSpeed = 0; ///< The speed in [°].
uint32_t windGusting = 0;
int32_t temperature = 0; ///< The temperature in [°C].
float humidity = 0.0;
uint32_t visibility = 0; ///< Visibility in [m].
uint32_t precipitation = 0; ///< The probability of precipitation in [%].
};
Q_DECLARE_METATYPE(WeatherInformation);
/**
* @class AirspaceManager
* Base class for airspace management. There is one (global) instantiation of this
*/
class AirspaceManager : public QGCTool {
Q_OBJECT
public:
AirspaceManager(QGCApplication* app, QGCToolbox* toolbox);
virtual ~AirspaceManager();
/**
* Factory method to create an AirspaceManagerPerVehicle object
*/
virtual AirspaceManagerPerVehicle* instantiateVehicle(const Vehicle& vehicle) = 0;
/**
* Factory method to create an AirspaceRestrictionProvider object
*/
virtual AirspaceRestrictionProvider* instantiateRestrictionProvider() = 0;
/**
* Factory method to create an AirspaceRulesetsProvider object
*/
virtual AirspaceRulesetsProvider* instantiateRulesetsProvider() = 0;
/**
* Set the ROI for airspace information (restrictions shown in UI)
* @param center Center coordinate for ROI
* @param radiusMeters Radius in meters around center which is of interest
*/
void setROI(const QGeoCoordinate& center, double radiusMeters);
QmlObjectListModel* polygonRestrictions(void) { return &_polygonRestrictions; }
QmlObjectListModel* circularRestrictions(void) { return &_circleRestrictions; }
void setToolbox(QGCToolbox* toolbox) override;
/**
* Name of the airspace management provider (used in the UI)
*/
virtual QString name() const = 0;
/**
* Request weather information update. When done, it will emit the weatherUpdate() signal.
* @param coordinate request update for this coordinate
*/
virtual void requestWeatherUpdate(const QGeoCoordinate& coordinate) = 0;
signals:
void weatherUpdate(bool success, QGeoCoordinate coordinate, WeatherInformation weather);
private slots:
void _restrictionsUpdated(bool success);
private:
void _updateToROI();
AirspaceRestrictionProvider* _restrictionsProvider = nullptr; ///< restrictions that are shown in the UI
AirspaceRulesetsProvider* _rulesetsProvider = nullptr; ///< restrictions that are shown in the UI
QmlObjectListModel _polygonRestrictions; ///< current polygon restrictions
QmlObjectListModel _circleRestrictions; ///< current circle restrictions
QTimer _roiUpdateTimer;
QGeoCoordinate _roiCenter;
double _roiRadius;
};
/**
* @class AirspaceManagerPerVehicle
* Base class for per-vehicle management (each vehicle has one (or zero) of these)
*/
class AirspaceManagerPerVehicle : public QObject {
Q_OBJECT
public:
AirspaceManagerPerVehicle(const Vehicle& vehicle);
virtual ~AirspaceManagerPerVehicle() = default;
/**
* create/upload a flight from a mission. This should update the flight permit status.
* There can only be one active flight for each vehicle.
*/
virtual void createFlight(const QList<MissionItem*>& missionItems) = 0;
/**
* get the current flight permit status
*/
virtual AirspaceAuthorization::PermitStatus flightPermitStatus() const = 0;
/**
* Setup the connection and start sending telemetry
*/
virtual void startTelemetryStream() = 0;
virtual void stopTelemetryStream() = 0;
virtual bool isTelemetryStreaming() const = 0;
public slots:
virtual void endFlight() = 0;
signals:
void trafficUpdate(QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading);
void flightPermitStatusChanged();
protected slots:
virtual void vehicleMavlinkMessageReceived(const mavlink_message_t& message) = 0;
protected:
const Vehicle& _vehicle;
private slots:
void _vehicleArmedChanged(bool armed);
private:
bool _vehicleWasInMissionMode = false; ///< true if the vehicle was in mission mode when arming
};

23
src/Airmap/AirspaceController.cc → src/AirspaceManagement/AirspaceController.cc

@ -19,8 +19,6 @@ @@ -19,8 +19,6 @@
AirspaceController::AirspaceController(QObject* parent)
: QObject(parent)
, _manager(qgcApp()->toolbox()->airspaceManager())
, _weatherTemp(0)
, _hasWeather(false)
{
connect(_manager, &AirspaceManager::weatherUpdate, this, &AirspaceController::_weatherUpdate);
}
@ -28,25 +26,4 @@ AirspaceController::AirspaceController(QObject* parent) @@ -28,25 +26,4 @@ AirspaceController::AirspaceController(QObject* parent)
void AirspaceController::setROI(QGeoCoordinate center, double radius)
{
_manager->setROI(center, radius);
//-- If first time or we've moved more than WEATHER_UPDATE_DISTANCE, ask for weather updates.
if(!_lastRoiCenter.isValid() || _lastRoiCenter.distanceTo(center) > WEATHER_UPDATE_DISTANCE) {
_lastRoiCenter = center;
_manager->requestWeatherUpdate(center);
_weatherTime.start();
} else {
//-- Check weather once every WEATHER_UPDATE_TIME
if(_weatherTime.elapsed() > WEATHER_UPDATE_TIME) {
_manager->requestWeatherUpdate(center);
_weatherTime.start();
}
}
}
void AirspaceController::_weatherUpdate(bool success, QGeoCoordinate, WeatherInformation weather)
{
qCDebug(AirMapManagerLog)<<"Weather Info:"<< success << weather.condition << weather.temperature;
_hasWeather = success;
_weatherIcon = QStringLiteral("qrc:/airmapweather/") + weather.condition + QStringLiteral(".svg");
_weatherTemp = weather.temperature;
emit weatherChanged();
}

37
src/AirspaceManagement/AirspaceController.h

@ -0,0 +1,37 @@ @@ -0,0 +1,37 @@
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "AirspaceManagement.h"
#include "QGCMapPolygon.h"
#include "AirmapWeatherInformation.h"
class AirspaceController : public QObject
{
Q_OBJECT
public:
AirspaceController(QObject* parent = NULL);
~AirspaceController() = default;
Q_PROPERTY(QmlObjectListModel* polygons READ polygons CONSTANT) ///< List of AirspacePolygonRestriction objects
Q_PROPERTY(QmlObjectListModel* circles READ circles CONSTANT) ///< List of AirspaceCircularRestriction objects
Q_PROPERTY(QString providerName READ providerName CONSTANT)
Q_PROPERTY(AirspaceWeatherInfoProvider* weatherInfo READ weatherInfo CONSTANT)
Q_INVOKABLE void setROI (QGeoCoordinate center, double radius);
QmlObjectListModel* polygons () { return _manager->polygonRestrictions(); }
QmlObjectListModel* circles () { return _manager->circularRestrictions(); }
QString providerName() { return _manager->name(); }
AirspaceWeatherInfoProvider* weatherInfo () { return _manager->weatherInfo(); }
private:
AirspaceManager* _manager;
};

114
src/AirspaceManagement/AirspaceManagement.cc

@ -0,0 +1,114 @@ @@ -0,0 +1,114 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "AirspaceManagement.h"
#include <Vehicle.h>
QGC_LOGGING_CATEGORY(AirspaceManagementLog, "AirspaceManagementLog")
AirspaceManager::AirspaceManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
{
_roiUpdateTimer.setInterval(2000);
_roiUpdateTimer.setSingleShot(true);
connect(&_roiUpdateTimer, &QTimer::timeout, this, &AirspaceManager::_updateToROI);
qmlRegisterUncreatableType<AirspaceAuthorization>("QGroundControl", 1, 0, "AirspaceAuthorization", "Reference only");
}
AirspaceManager::~AirspaceManager()
{
if (_restrictionsProvider) {
delete _restrictionsProvider;
}
if(_rulesetsProvider) {
delete _rulesetsProvider;
}
_polygonRestrictions.clearAndDeleteContents();
_circleRestrictions.clearAndDeleteContents();
}
void AirspaceManager::setToolbox(QGCToolbox* toolbox)
{
QGCTool::setToolbox(toolbox);
// We should not call virtual methods in the constructor, so we instantiate the restriction provider here
_restrictionsProvider = instantiateRestrictionProvider();
if (_restrictionsProvider) {
connect(_restrictionsProvider, &AirspaceRestrictionProvider::requestDone, this, &AirspaceManager::_restrictionsUpdated);
}
_rulesetsProvider = instantiateRulesetsProvider();
if (_rulesetsProvider) {
connect(_rulesetsProvider, &AirspaceRulesetsProvider::requestDone, this, &AirspaceManager::_rulessetsUpdated);
}
_weatherProvider = instatiateAirspaceWeatherInfoProvider();
}
void AirspaceManager::setROI(const QGeoCoordinate& center, double radiusMeters)
{
_roiCenter = center;
_roiRadius = radiusMeters;
_roiUpdateTimer.start();
}
void AirspaceManager::_updateToROI()
{
if (_restrictionsProvider) {
_restrictionsProvider->setROI(_roiCenter, _roiRadius);
}
if(_rulesetsProvider) {
_rulesetsProvider->setROI(_roiCenter);
}
if(_weatherProvider) {
_weatherProvider->setROI(_roiCenter);
}
}
void AirspaceManager::_restrictionsUpdated(bool success)
{
_polygonRestrictions.clearAndDeleteContents();
_circleRestrictions.clearAndDeleteContents();
if (success) {
for (const auto& circle : _restrictionsProvider->circles()) {
_circleRestrictions.append(circle);
}
for (const auto& polygon : _restrictionsProvider->polygons()) {
_polygonRestrictions.append(polygon);
}
} else {
// TODO: show error?
}
}
void AirspaceManager::_rulessetsUpdated(bool)
{
}
AirspaceVehicleManager::AirspaceVehicleManager(const Vehicle& vehicle)
: _vehicle(vehicle)
{
connect(&_vehicle, &Vehicle::armedChanged, this, &AirspaceVehicleManager::_vehicleArmedChanged);
connect(&_vehicle, &Vehicle::mavlinkMessageReceived, this, &AirspaceVehicleManager::vehicleMavlinkMessageReceived);
}
void AirspaceVehicleManager::_vehicleArmedChanged(bool armed)
{
if (armed) {
startTelemetryStream();
_vehicleWasInMissionMode = _vehicle.flightMode() == _vehicle.missionFlightMode();
} else {
stopTelemetryStream();
// end the flight if we were in mission mode during arming or disarming
// TODO: needs to be improved. for instance if we do RTL and then want to continue the mission...
if (_vehicleWasInMissionMode || _vehicle.flightMode() == _vehicle.missionFlightMode()) {
endFlight();
}
}
}

138
src/AirspaceManagement/AirspaceManagement.h

@ -0,0 +1,138 @@ @@ -0,0 +1,138 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
/**
* @file AirspaceManagement.h
* This file contains the interface definitions used by an airspace management implementation (AirMap).
* There are 3 base classes that must be subclassed:
* - AirspaceManager
* main manager that contains the restrictions for display. It acts as a factory to create instances of the other
* classes.
* - AirspaceVehicleManager
* this provides the multi-vehicle support - each vehicle has an instance
* - AirspaceRestrictionProvider
* provides airspace restrictions. Currently only used by AirspaceManager, but
* each vehicle could have its own restrictions.
*/
#include "QGCToolbox.h"
#include "MissionItem.h"
#include <QObject>
#include <QString>
#include <QList>
#include <QGCLoggingCategory.h>
Q_DECLARE_LOGGING_CATEGORY(AirspaceManagementLog)
class AirMapWeatherInformation;
//-----------------------------------------------------------------------------
/**
* Contains the status of the Airspace authorization
*/
class AirspaceAuthorization : public QObject {
Q_OBJECT
public:
enum PermitStatus {
PermitUnknown = 0,
PermitPending,
PermitAccepted,
PermitRejected,
};
Q_ENUMS(PermitStatus);
};
class AirspaceRestrictionProvider;
class AirspaceRulesetsProvider;
class AirspaceVehicleManager;
class AirspaceWeatherInfoProvider;
class Vehicle;
//-----------------------------------------------------------------------------
/**
* @class AirspaceManager
* Base class for airspace management. There is one (global) instantiation of this
*/
class AirspaceManager : public QGCTool {
Q_OBJECT
public:
AirspaceManager(QGCApplication* app, QGCToolbox* toolbox);
virtual ~AirspaceManager();
/**
* Factory method to create an AirspaceVehicleManager object
*/
virtual AirspaceVehicleManager* instantiateVehicle (const Vehicle& vehicle) = 0;
/**
* Factory method to create an AirspaceRestrictionProvider object
*/
virtual AirspaceRestrictionProvider* instantiateRestrictionProvider () = 0;
/**
* Factory method to create an AirspaceRulesetsProvider object
*/
virtual AirspaceRulesetsProvider* instantiateRulesetsProvider () = 0;
/**
* Factory method to create an AirspaceRulesetsProvider object
*/
virtual AirspaceWeatherInfoProvider* instatiateAirspaceWeatherInfoProvider () = 0;
/**
* Set the ROI for airspace information (restrictions shown in UI)
* @param center Center coordinate for ROI
* @param radiusMeters Radius in meters around center which is of interest
*/
void setROI (const QGeoCoordinate& center, double radiusMeters);
QmlObjectListModel* polygonRestrictions () { return &_polygonRestrictions; }
QmlObjectListModel* circularRestrictions () { return &_circleRestrictions; }
AirspaceWeatherInfoProvider* weatherInfo () { return _weather;}
void setToolbox(QGCToolbox* toolbox) override;
/**
* Name of the airspace management provider (used in the UI)
*/
virtual QString name () const = 0;
/**
* Request weather information update. When done, it will emit the weatherUpdate() signal.
* @param coordinate request update for this coordinate
*/
virtual void requestWeatherUpdate(const QGeoCoordinate& coordinate) = 0;
signals:
void weatherUpdate (bool success, QGeoCoordinate coordinate, WeatherInformation weather);
protected slots:
virtual void _rulessetsUpdated (bool success);
private slots:
void _restrictionsUpdated (bool success);
private:
void _updateToROI ();
AirspaceRestrictionProvider* _restrictionsProvider = nullptr; ///< Restrictions that are shown in the UI
AirspaceRulesetsProvider* _rulesetsProvider = nullptr; ///< Restrictions that are shown in the UI
AirspaceWeatherInfoProvider* _weatherProvider = nullptr; ///< Weather info that is shown in the UI
QmlObjectListModel _polygonRestrictions; ///< current polygon restrictions
QmlObjectListModel _circleRestrictions; ///< current circle restrictions
QTimer _roiUpdateTimer;
QGeoCoordinate _roiCenter;
double _roiRadius;
AirspaceWeatherInfoProvider* _weather;
};

31
src/AirspaceManagement/AirspaceRestriction.cc

@ -0,0 +1,31 @@ @@ -0,0 +1,31 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "AirspaceRestriction.h"
AirspaceRestriction::AirspaceRestriction(QObject* parent)
: QObject(parent)
{
}
AirspacePolygonRestriction::AirspacePolygonRestriction(const QVariantList& polygon, QObject* parent)
: AirspaceRestriction(parent)
, _polygon(polygon)
{
}
AirspaceCircularRestriction::AirspaceCircularRestriction(const QGeoCoordinate& center, double radius, QObject* parent)
: AirspaceRestriction(parent)
, _center(center)
, _radius(radius)
{
}

64
src/AirspaceManagement/AirspaceRestriction.h

@ -0,0 +1,64 @@ @@ -0,0 +1,64 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include <QObject>
#include <QGeoCoordinate>
/**
* @class AirspaceRestriction
* Base classe for an airspace restriction
*/
class AirspaceRestriction : public QObject
{
Q_OBJECT
public:
AirspaceRestriction(QObject* parent = NULL);
};
/**
* @class AirspacePolygonRestriction
* Base classe for an airspace restriction defined by a polygon
*/
class AirspacePolygonRestriction : public AirspaceRestriction
{
Q_OBJECT
public:
AirspacePolygonRestriction(const QVariantList& polygon, QObject* parent = NULL);
Q_PROPERTY(QVariantList polygon MEMBER _polygon CONSTANT)
const QVariantList& getPolygon() const { return _polygon; }
private:
QVariantList _polygon;
};
/**
* @class AirspaceRestriction
* Base classe for an airspace restriction defined by a circle
*/
class AirspaceCircularRestriction : public AirspaceRestriction
{
Q_OBJECT
public:
AirspaceCircularRestriction(const QGeoCoordinate& center, double radius, QObject* parent = NULL);
Q_PROPERTY(QGeoCoordinate center MEMBER _center CONSTANT)
Q_PROPERTY(double radius MEMBER _radius CONSTANT)
private:
QGeoCoordinate _center;
double _radius;
};

15
src/AirspaceManagement/AirspaceRestrictionProvider.cc

@ -0,0 +1,15 @@ @@ -0,0 +1,15 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "AirspaceRestrictionProvider.h"
AirspaceRestrictionProvider::AirspaceRestrictionProvider(QObject *parent)
: QObject(parent)
{
}

42
src/AirspaceManagement/AirspaceRestrictionProvider.h

@ -0,0 +1,42 @@ @@ -0,0 +1,42 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
/**
* @class AirspaceRestrictionProvider
* Base class that queries for airspace restrictions
*/
#include <QObject>
#include "AirspaceRestriction.h"
class AirspaceRestrictionProvider : public QObject {
Q_OBJECT
public:
AirspaceRestrictionProvider (QObject* parent = NULL);
~AirspaceRestrictionProvider () = default;
/**
* Set region of interest that should be queried. When finished, the requestDone() signal will be emmited.
* @param center Center coordinate for ROI
* @param radiusMeters Radius in meters around center which is of interest
*/
virtual void setROI (const QGeoCoordinate& center, double radiusMeters) = 0;
const QList<AirspacePolygonRestriction*>& polygons() const { return _polygonList; }
const QList<AirspaceCircularRestriction*>& circles () const { return _circleList; }
signals:
void requestDone (bool success);
protected:
QList<AirspacePolygonRestriction*> _polygonList;
QList<AirspaceCircularRestriction*> _circleList;
};

15
src/AirspaceManagement/AirspaceRulesetsProvider.cc

@ -0,0 +1,15 @@ @@ -0,0 +1,15 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "AirspaceRulesetsProvider.h"
AirspaceRulesetsProvider::AirspaceRulesetsProvider(QObject *parent)
: QObject(parent)
{
}

34
src/AirspaceManagement/AirspaceRulesetsProvider.h

@ -0,0 +1,34 @@ @@ -0,0 +1,34 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
//-----------------------------------------------------------------------------
/**
* @class AirspaceRulesetsProvider
* Base class that queries for airspace rulesets
*/
#include <QObject>
#include <QGeoCoordinate.h>
class AirspaceRulesetsProvider : public QObject {
Q_OBJECT
public:
AirspaceRulesetsProvider (QObject* parent = NULL);
~AirspaceRulesetsProvider () = default;
/**
* Set region of interest that should be queried. When finished, the requestDone() signal will be emmited.
* @param center Center coordinate for ROI
*/
virtual void setROI (const QGeoCoordinate& center) = 0;
signals:
void requestDone (bool success);
};

42
src/Airmap/AirspaceManagement.cc → src/AirspaceManagement/AirspaceVehicleManager.cc

@ -13,28 +13,6 @@ @@ -13,28 +13,6 @@
QGC_LOGGING_CATEGORY(AirspaceManagementLog, "AirspaceManagementLog")
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)
{
}
AirspaceManager::AirspaceManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
{
@ -42,7 +20,6 @@ AirspaceManager::AirspaceManager(QGCApplication* app, QGCToolbox* toolbox) @@ -42,7 +20,6 @@ AirspaceManager::AirspaceManager(QGCApplication* app, QGCToolbox* toolbox)
_roiUpdateTimer.setSingleShot(true);
connect(&_roiUpdateTimer, &QTimer::timeout, this, &AirspaceManager::_updateToROI);
qmlRegisterUncreatableType<AirspaceAuthorization>("QGroundControl", 1, 0, "AirspaceAuthorization", "Reference only");
qRegisterMetaType<WeatherInformation>();
}
AirspaceManager::~AirspaceManager()
@ -60,20 +37,17 @@ AirspaceManager::~AirspaceManager() @@ -60,20 +37,17 @@ AirspaceManager::~AirspaceManager()
void AirspaceManager::setToolbox(QGCToolbox* toolbox)
{
QGCTool::setToolbox(toolbox);
// we should not call virtual methods in the constructor, so we instantiate the restriction provider here
// We should not call virtual methods in the constructor, so we instantiate the restriction provider here
_restrictionsProvider = instantiateRestrictionProvider();
if (_restrictionsProvider) {
connect(_restrictionsProvider, &AirspaceRestrictionProvider::requestDone, this,
&AirspaceManager::_restrictionsUpdated);
}
_rulesetsProvider = instantiateRulesetsProvider();
/*
if (_rulesetsProvider) {
connect(_rulesetsProvider, &AirspaceRulesetsProvider::requestDone, this,
&AirspaceManager::_rulesetsUpdated);
&AirspaceManager::_rulessetsUpdated);
}
*/
}
void AirspaceManager::setROI(const QGeoCoordinate& center, double radiusMeters)
@ -111,15 +85,19 @@ void AirspaceManager::_restrictionsUpdated(bool success) @@ -111,15 +85,19 @@ void AirspaceManager::_restrictionsUpdated(bool success)
}
}
void AirspaceManager::_rulessetsUpdated(bool)
{
}
AirspaceManagerPerVehicle::AirspaceManagerPerVehicle(const Vehicle& vehicle)
AirspaceVehicleManager::AirspaceVehicleManager(const Vehicle& vehicle)
: _vehicle(vehicle)
{
connect(&_vehicle, &Vehicle::armedChanged, this, &AirspaceManagerPerVehicle::_vehicleArmedChanged);
connect(&_vehicle, &Vehicle::mavlinkMessageReceived, this, &AirspaceManagerPerVehicle::vehicleMavlinkMessageReceived);
connect(&_vehicle, &Vehicle::armedChanged, this, &AirspaceVehicleManager::_vehicleArmedChanged);
connect(&_vehicle, &Vehicle::mavlinkMessageReceived, this, &AirspaceVehicleManager::vehicleMavlinkMessageReceived);
}
void AirspaceManagerPerVehicle::_vehicleArmedChanged(bool armed)
void AirspaceVehicleManager::_vehicleArmedChanged(bool armed)
{
if (armed) {
startTelemetryStream();

64
src/AirspaceManagement/AirspaceVehicleManager.h

@ -0,0 +1,64 @@ @@ -0,0 +1,64 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include <QList>
class Vehicle;
//-----------------------------------------------------------------------------
/**
* @class AirspaceVehicleManager
* Base class for per-vehicle management (each vehicle has one (or zero) of these)
*/
class AirspaceVehicleManager : public QObject {
Q_OBJECT
public:
AirspaceVehicleManager (const Vehicle& vehicle);
virtual ~AirspaceVehicleManager () = default;
/**
* create/upload a flight from a mission. This should update the flight permit status.
* There can only be one active flight for each vehicle.
*/
virtual void createFlight (const QList<MissionItem*>& missionItems) = 0;
/**
* get the current flight permit status
*/
virtual AirspaceAuthorization::PermitStatus flightPermitStatus() const = 0;
/**
* Setup the connection and start sending telemetry
*/
virtual void startTelemetryStream () = 0;
virtual void stopTelemetryStream () = 0;
virtual bool isTelemetryStreaming () const = 0;
public slots:
virtual void endFlight () = 0;
signals:
void trafficUpdate (QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading);
void flightPermitStatusChanged ();
protected slots:
virtual void vehicleMavlinkMessageReceived(const mavlink_message_t& message) = 0;
protected:
const Vehicle& _vehicle;
private slots:
void _vehicleArmedChanged (bool armed);
private:
bool _vehicleWasInMissionMode = false; ///< true if the vehicle was in mission mode when arming
};

15
src/AirspaceManagement/AirspaceWeatherInfoProvider.cc

@ -0,0 +1,15 @@ @@ -0,0 +1,15 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "AirspaceWeatherInfoProvider.h"
AirspaceWeatherInfoProvider::AirspaceWeatherInfoProvider(QObject *parent)
: QObject(parent)
{
}

56
src/AirspaceManagement/AirspaceWeatherInfoProvider.h

@ -0,0 +1,56 @@ @@ -0,0 +1,56 @@
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
/**
* @file AirspaceWeatherInfoProvider.h
* Weather information provided by the Airspace Managemement
*/
#include <QObject>
class AirspaceWeatherInfoProvider : public QObject
{
Q_OBJECT
public:
AirspaceWeatherInfoProvider(QObject *parent = nullptr);
virtual ~AirspaceWeatherInfoProvider() {}
Q_PROPERTY(bool valid READ valid NOTIFY weatherChanged)
Q_PROPERTY(QString condition READ condition NOTIFY weatherChanged)
Q_PROPERTY(QString icon READ icon NOTIFY weatherChanged)
Q_PROPERTY(quint32 windHeading READ windHeading NOTIFY weatherChanged)
Q_PROPERTY(quint32 windSpeed READ windSpeed NOTIFY weatherChanged)
Q_PROPERTY(quint32 windGusting READ windGusting NOTIFY weatherChanged)
Q_PROPERTY(qint32 temperature READ temperature NOTIFY weatherChanged)
Q_PROPERTY(float humidity READ humidity NOTIFY weatherChanged)
Q_PROPERTY(quint32 visibility READ visibility NOTIFY weatherChanged)
Q_PROPERTY(quint32 precipitation READ precipitation NOTIFY weatherChanged)
virtual bool valid () = 0; ///< Current weather data is valid
virtual QString condition () = 0; ///< The overall weather condition.
virtual QString icon () = 0; ///< 2:1 Aspect ratio icon url ready to be used by an Image QML Item
virtual quint32 windHeading () = 0; ///< The heading in [°].
virtual quint32 windSpeed () = 0; ///< The speed in [°].
virtual quint32 windGusting () = 0;
virtual qint32 temperature () = 0; ///< The temperature in [°C].
virtual float humidity () = 0;
virtual quint32 visibility () = 0; ///< Visibility in [m].
virtual quint32 precipitation () = 0; ///< The probability of precipitation in [%].
/**
* Set region of interest that should be queried. When finished, the weatherChanged() signal will be emmited.
* @param center Center coordinate for ROI
*/
virtual void setROI (const QGeoCoordinate& center) = 0;
signals:
void weatherChanged ();
};

2
src/MissionManager/PlanManager.cc

@ -81,7 +81,7 @@ void PlanManager::writeMissionItems(const QList<MissionItem*>& missionItems) @@ -81,7 +81,7 @@ void PlanManager::writeMissionItems(const QList<MissionItem*>& missionItems)
if (_planType == MAV_MISSION_TYPE_MISSION) {
#if defined(QGC_AIRMAP_ENABLED)
// upload the flight to the airspace management backend
AirspaceManagerPerVehicle* airspaceManager = _vehicle->airspaceManager();
AirspaceVehicleManager* airspaceManager = _vehicle->airspaceManager();
if (airspaceManager) {
airspaceManager->createFlight(missionItems);
}

4
src/QGCApplication.cc

@ -86,6 +86,7 @@ @@ -86,6 +86,7 @@
#include "EditPositionDialogController.h"
#if defined(QGC_AIRMAP_ENABLED)
#include "AirspaceController.h"
#include "AirmapWeatherInformation.h"
#endif
#ifndef NO_SERIAL_LINK
#include "SerialLink.h"
@ -384,7 +385,8 @@ void QGCApplication::_initCommon(void) @@ -384,7 +385,8 @@ void QGCApplication::_initCommon(void)
qmlRegisterUncreatableType<RallyPointController>("QGroundControl.Controllers", 1, 0, "RallyPointController", "Reference only");
qmlRegisterUncreatableType<VisualMissionItem> ("QGroundControl.Controllers", 1, 0, "VisualMissionItem", "Reference only");
#if defined(QGC_AIRMAP_ENABLED)
qmlRegisterUncreatableType<AirspaceController> ("QGroundControl.Vehicle", 1, 0, "AirspaceController", "Reference only");
qmlRegisterUncreatableType<AirspaceController> ("QGroundControl.Vehicle", 1, 0, "AirspaceController", "Reference only");
qmlRegisterUncreatableType<AirMapWeatherInformation> ("QGroundControl.Vehicle", 1, 0, "AirMapWeatherInformation", "Reference only");
#endif
qmlRegisterType<ParameterEditorController> ("QGroundControl.Controllers", 1, 0, "ParameterEditorController");

3
src/QGCToolbox.cc

@ -86,6 +86,9 @@ QGCToolbox::QGCToolbox(QGCApplication* app) @@ -86,6 +86,9 @@ QGCToolbox::QGCToolbox(QGCApplication* app)
_followMe = new FollowMe (app, this);
_videoManager = new VideoManager (app, this);
_mavlinkLogManager = new MAVLinkLogManager (app, this);
//-- Airmap Manager
//-- This should be "pluggable" so an arbitrary AirSpace manager can be used
//-- For now, we instantiate the one and only AirMap provider
#if defined(QGC_AIRMAP_ENABLED)
_airspaceManager = new AirMapManager (app, this);
#endif

4
src/Vehicle/Vehicle.cc

@ -274,8 +274,8 @@ Vehicle::Vehicle(LinkInterface* link, @@ -274,8 +274,8 @@ Vehicle::Vehicle(LinkInterface* link,
if (airspaceManager) {
_airspaceManagerPerVehicle = airspaceManager->instantiateVehicle(*this);
if (_airspaceManagerPerVehicle) {
connect(_airspaceManagerPerVehicle, &AirspaceManagerPerVehicle::trafficUpdate, this, &Vehicle::_trafficUpdate);
connect(_airspaceManagerPerVehicle, &AirspaceManagerPerVehicle::flightPermitStatusChanged, this, &Vehicle::flightPermitStatusChanged);
connect(_airspaceManagerPerVehicle, &AirspaceVehicleManager::trafficUpdate, this, &Vehicle::_trafficUpdate);
connect(_airspaceManagerPerVehicle, &AirspaceVehicleManager::flightPermitStatusChanged, this, &Vehicle::flightPermitStatusChanged);
}
}
#endif

4
src/Vehicle/Vehicle.h

@ -771,7 +771,7 @@ public: @@ -771,7 +771,7 @@ public:
AirspaceAuthorization::PermitStatus flightPermitStatus() const
{ return _airspaceManagerPerVehicle ? _airspaceManagerPerVehicle->flightPermitStatus() : AirspaceAuthorization::PermitUnknown; }
AirspaceManagerPerVehicle* airspaceManager() const { return _airspaceManagerPerVehicle; }
AirspaceVehicleManager* airspaceManager() const { return _airspaceManagerPerVehicle; }
#endif
signals:
@ -1066,7 +1066,7 @@ private: @@ -1066,7 +1066,7 @@ private:
#if defined(QGC_AIRMAP_ENABLED)
AirspaceController* _airspaceController;
AirspaceManagerPerVehicle* _airspaceManagerPerVehicle;
AirspaceVehicleManager* _airspaceManagerPerVehicle;
#endif
bool _armed; ///< true: vehicle is armed

Loading…
Cancel
Save