diff --git a/QGCExternalLibs.pri b/QGCExternalLibs.pri
index 506884f6f095b169d8b685a827bb78a8eea397c9..7d47a982ac0bf81f2f251a88c0c1ed1f8e8814a0 100644
--- a/QGCExternalLibs.pri
+++ b/QGCExternalLibs.pri
@@ -124,3 +124,24 @@ contains (DEFINES, DISABLE_ZEROCONF) {
message("Skipping support for Zeroconf (unsupported platform)")
}
+
+#
+# [OPTIONAL] AirMap Support
+#
+contains (DEFINES, DISABLE_AIRMAP) {
+ message("Skipping support for AirMap (manual override from command line)")
+# Otherwise the user can still disable this feature in the user_config.pri file.
+} else:exists(user_config.pri):infile(user_config.pri, DEFINES, DISABLE_AIRMAP) {
+ message("Skipping support for AirMap (manual override from user_config.pri)")
+} else {
+ AIRMAPD_PATH = $$PWD/libs/airmapd
+ INCLUDEPATH += \
+ $${AIRMAPD_PATH}/include
+ MacBuild|iOSBuild {
+ message("Including support for AirMap")
+ LIBS += -L$${AIRMAPD_PATH}/macOS/Qt.5.9 -lairmap-qt
+ DEFINES += QGC_AIRMAP_ENABLED
+ } else {
+ message("Skipping support for Airmap (unsupported platform)")
+ }
+}
diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index 1609e178c8b4a21dcb710a0d5633787d8ebe40d2..7c9f0fe8f6a4ce2e577f8d4ed1076b99342bab64 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -505,6 +505,9 @@ HEADERS += \
src/LogCompressor.h \
src/MG.h \
src/MissionManager/CameraCalc.h \
+ src/MissionManager/AirspaceController.h \
+ src/MissionManager/AirMapManager.h \
+ src/MissionManager/AirspaceManagement.h \
src/MissionManager/CameraSection.h \
src/MissionManager/CameraSpec.h \
src/MissionManager/ComplexMissionItem.h \
@@ -564,6 +567,7 @@ HEADERS += \
src/QmlControls/RCChannelMonitorController.h \
src/QmlControls/ScreenToolsController.h \
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h \
+ src/Settings/AirMapSettings.h \
src/Settings/AppSettings.h \
src/Settings/AutoConnectSettings.h \
src/Settings/BrandImageSettings.h \
@@ -697,6 +701,9 @@ SOURCES += \
src/JsonHelper.cc \
src/LogCompressor.cc \
src/MissionManager/CameraCalc.cc \
+ src/MissionManager/AirspaceController.cc \
+ src/MissionManager/AirMapManager.cc \
+ src/MissionManager/AirspaceManagement.cc \
src/MissionManager/CameraSection.cc \
src/MissionManager/CameraSpec.cc \
src/MissionManager/ComplexMissionItem.cc \
@@ -753,6 +760,7 @@ SOURCES += \
src/QmlControls/RCChannelMonitorController.cc \
src/QmlControls/ScreenToolsController.cc \
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc \
+ src/Settings/AirMapSettings.cc \
src/Settings/AppSettings.cc \
src/Settings/AutoConnectSettings.cc \
src/Settings/BrandImageSettings.cc \
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index b1d47d0ba5d409401e464f6fad50b1fe9d9c1b69..9d399d646731ae4dc731a81912a0de94f18a3873 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -199,6 +199,7 @@
src/MissionManager/MavCmdInfoRover.json
src/MissionManager/MavCmdInfoSub.json
src/MissionManager/MavCmdInfoVTOL.json
+ src/Settings/AirMap.SettingsGroup.json
src/Settings/App.SettingsGroup.json
src/Settings/AutoConnect.SettingsGroup.json
src/Settings/FlightMap.SettingsGroup.json
diff --git a/src/FlightDisplay/FlightDisplayView.qml b/src/FlightDisplay/FlightDisplayView.qml
index 2404e2967e3ba9ddc338622af827b17382ffbb74..3542909f1d4d7e9315d00c669ec263db001b91fa 100644
--- a/src/FlightDisplay/FlightDisplayView.qml
+++ b/src/FlightDisplay/FlightDisplayView.qml
@@ -626,4 +626,51 @@ QGCView {
visible: false
}
}
+
+ //-- Airspace Indicator
+ Rectangle {
+ id: airspaceIndicator
+ width: airspaceRow.width + (ScreenTools.defaultFontPixelWidth * 3)
+ height: airspaceRow.height * 1.25
+ color: qgcPal.globalTheme === QGCPalette.Light ? Qt.rgba(1,1,1,0.95) : Qt.rgba(0,0,0,0.75)
+ visible: _mainIsMap && flightPermit && flightPermit !== AirspaceAuthorization.PermitUnknown && !messageArea.visible && !criticalMmessageArea.visible
+ radius: 3
+ border.width: 1
+ border.color: qgcPal.globalTheme === QGCPalette.Light ? Qt.rgba(0,0,0,0.35) : Qt.rgba(1,1,1,0.35)
+ anchors.top: parent.top
+ anchors.topMargin: ScreenTools.toolbarHeight + (ScreenTools.defaultFontPixelHeight * 0.25)
+ anchors.horizontalCenter: parent.horizontalCenter
+ Row {
+ id: airspaceRow
+ spacing: ScreenTools.defaultFontPixelWidth
+ anchors.centerIn: parent
+ QGCLabel { text: airspaceIndicator.providerName+":"; anchors.verticalCenter: parent.verticalCenter; }
+ QGCLabel {
+ text: {
+ if(airspaceIndicator.flightPermit) {
+ if(airspaceIndicator.flightPermit === AirspaceAuthorization.PermitPending)
+ return qsTr("Approval Pending")
+ if(airspaceIndicator.flightPermit === AirspaceAuthorization.PermitAccepted)
+ return qsTr("Flight Approved")
+ if(airspaceIndicator.flightPermit === AirspaceAuthorization.PermitRejected)
+ return qsTr("Flight Rejected")
+ }
+ return ""
+ }
+ color: {
+ if(airspaceIndicator.flightPermit) {
+ if(airspaceIndicator.flightPermit === AirspaceAuthorization.PermitPending)
+ return qgcPal.colorOrange
+ if(airspaceIndicator.flightPermit === AirspaceAuthorization.PermitAccepted)
+ return qgcPal.colorGreen
+ }
+ return qgcPal.colorRed
+ }
+ anchors.verticalCenter: parent.verticalCenter;
+ }
+ }
+ property var flightPermit: _activeVehicle ? _activeVehicle.flightPermitStatus : null
+ property var providerName: _activeVehicle ? _activeVehicle.airspaceController.providerName : ""
+ }
+
}
diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml
index df01d8b74fda9ff6ae0c5fafd7a0188c615a333b..281d78967fb20769f02004cd185a0cc6237e7b6b 100644
--- a/src/FlightDisplay/FlightDisplayViewMap.qml
+++ b/src/FlightDisplay/FlightDisplayViewMap.qml
@@ -57,7 +57,12 @@ FlightMap {
// Track last known map position and zoom from Fly view in settings
onZoomLevelChanged: QGroundControl.flightMapZoom = zoomLevel
- onCenterChanged: QGroundControl.flightMapPosition = center
+ onCenterChanged: {
+ if(_activeVehicle) {
+ _activeVehicle.airspaceController.setROI(center, 5000)
+ }
+ QGroundControl.flightMapPosition = center
+ }
// When the user pans the map we stop responding to vehicle coordinate updates until the panRecenterTimer fires
onUserPannedChanged: {
@@ -323,4 +328,26 @@ FlightMap {
}
]
}
+
+ // Airspace overlap support
+ MapItemView {
+ model: _activeVehicle ? _activeVehicle.airspaceController.circles : []
+ delegate: MapCircle {
+ center: object.center
+ radius: object.radius
+ border.color: "white"
+ color: "yellow"
+ opacity: 0.25
+ }
+ }
+
+ MapItemView {
+ model: _activeVehicle ? _activeVehicle.airspaceController.polygons : []
+ delegate: MapPolygon {
+ border.color: "white"
+ color: "yellow"
+ opacity: 0.25
+ path: object.polygon
+ }
+ }
}
diff --git a/src/JsonHelper.cc b/src/JsonHelper.cc
index e7d47a6187a94fc4ab8288b64d3e7dcd8e8d449a..502f5a5cf837acda8c05d3a6a7ff70c970dba3ff 100644
--- a/src/JsonHelper.cc
+++ b/src/JsonHelper.cc
@@ -45,10 +45,11 @@ bool JsonHelper::validateRequiredKeys(const QJsonObject& jsonObject, const QStri
return true;
}
-bool JsonHelper::loadGeoCoordinate(const QJsonValue& jsonValue,
- bool altitudeRequired,
- QGeoCoordinate& coordinate,
- QString& errorString)
+bool JsonHelper::_loadGeoCoordinate(const QJsonValue& jsonValue,
+ bool altitudeRequired,
+ QGeoCoordinate& coordinate,
+ QString& errorString,
+ bool geoJsonFormat)
{
if (!jsonValue.isArray()) {
errorString = QObject::tr("value for coordinate is not array");
@@ -69,7 +70,11 @@ bool JsonHelper::loadGeoCoordinate(const QJsonValue& jsonValue,
}
}
- coordinate = QGeoCoordinate(possibleNaNJsonValue(coordinateArray[0]), possibleNaNJsonValue(coordinateArray[1]));
+ if (geoJsonFormat) {
+ coordinate = QGeoCoordinate(coordinateArray[1].toDouble(), coordinateArray[0].toDouble());
+ } else {
+ coordinate = QGeoCoordinate(possibleNaNJsonValue(coordinateArray[0]), possibleNaNJsonValue(coordinateArray[1]));
+ }
if (altitudeRequired) {
coordinate.setAltitude(possibleNaNJsonValue(coordinateArray[2]));
}
@@ -77,13 +82,18 @@ bool JsonHelper::loadGeoCoordinate(const QJsonValue& jsonValue,
return true;
}
-void JsonHelper::saveGeoCoordinate(const QGeoCoordinate& coordinate,
- bool writeAltitude,
- QJsonValue& jsonValue)
+void JsonHelper::_saveGeoCoordinate(const QGeoCoordinate& coordinate,
+ bool writeAltitude,
+ QJsonValue& jsonValue,
+ bool geoJsonFormat)
{
QJsonArray coordinateArray;
- coordinateArray << coordinate.latitude() << coordinate.longitude();
+ if (geoJsonFormat) {
+ coordinateArray << coordinate.longitude() << coordinate.latitude();
+ } else {
+ coordinateArray << coordinate.latitude() << coordinate.longitude();
+ }
if (writeAltitude) {
coordinateArray << coordinate.altitude();
}
@@ -91,6 +101,37 @@ void JsonHelper::saveGeoCoordinate(const QGeoCoordinate& coordinate,
jsonValue = QJsonValue(coordinateArray);
}
+bool JsonHelper::loadGeoCoordinate(const QJsonValue& jsonValue,
+ bool altitudeRequired,
+ QGeoCoordinate& coordinate,
+ QString& errorString,
+ bool geoJsonFormat)
+{
+ return _loadGeoCoordinate(jsonValue, altitudeRequired, coordinate, errorString, geoJsonFormat);
+}
+
+void JsonHelper::saveGeoCoordinate(const QGeoCoordinate& coordinate,
+ bool writeAltitude,
+ QJsonValue& jsonValue)
+{
+ _saveGeoCoordinate(coordinate, writeAltitude, jsonValue, false /* geoJsonFormat */);
+}
+
+bool JsonHelper::loadGeoJsonCoordinate(const QJsonValue& jsonValue,
+ bool altitudeRequired,
+ QGeoCoordinate& coordinate,
+ QString& errorString)
+{
+ return _loadGeoCoordinate(jsonValue, altitudeRequired, coordinate, errorString, true /* geoJsonFormat */);
+}
+
+void JsonHelper::saveGeoJsonCoordinate(const QGeoCoordinate& coordinate,
+ bool writeAltitude,
+ QJsonValue& jsonValue)
+{
+ _saveGeoCoordinate(coordinate, writeAltitude, jsonValue, true /* geoJsonFormat */);
+}
+
bool JsonHelper::validateKeyTypes(const QJsonObject& jsonObject, const QStringList& keys, const QList& types, QString& errorString)
{
for (int i=0; i& keyInfo, QString& errorString);
/// Loads a QGeoCoordinate
+ /// Stored as array [ lat, lon, alt ]
/// @return false: validation failed
- static bool loadGeoCoordinate(const QJsonValue& jsonValue, ///< json value to load from
- bool altitudeRequired, ///< true: altitude must be specified
- QGeoCoordinate& coordinate, ///< returned QGeoCordinate
- QString& errorString); ///< returned error string if load failure
+ static bool loadGeoCoordinate(const QJsonValue& jsonValue, ///< json value to load from
+ bool altitudeRequired, ///< true: altitude must be specified
+ QGeoCoordinate& coordinate, ///< returned QGeoCordinate
+ QString& errorString, ///< returned error string if load failure
+ bool geoJsonFormat = false); ///< if true, use [lon, lat], [lat, lon] otherwise
+
+ /// Saves a QGeoCoordinate
+ /// Stored as array [ lat, lon, alt ]
+ static void saveGeoCoordinate(const QGeoCoordinate& coordinate, ///< QGeoCoordinate to save
+ bool writeAltitude, ///< true: write altitude to json
+ QJsonValue& jsonValue); ///< json value to save to
+
+ /// Loads a QGeoCoordinate
+ /// Stored as array [ lon, lat, alt ]
+ /// @return false: validation failed
+ static bool loadGeoJsonCoordinate(const QJsonValue& jsonValue, ///< json value to load from
+ bool altitudeRequired, ///< true: altitude must be specified
+ QGeoCoordinate& coordinate, ///< returned QGeoCordinate
+ QString& errorString); ///< returned error string if load failure
+
+ /// Saves a QGeoCoordinate
+ /// Stored as array [ lon, lat, alt ]
+ static void saveGeoJsonCoordinate(const QGeoCoordinate& coordinate, ///< QGeoCoordinate to save
+ bool writeAltitude, ///< true: write altitude to json
+ QJsonValue& jsonValue); ///< json value to save to
/// Loads a polygon from an array
static bool loadPolygon(const QJsonArray& polygonArray, ///< Array of coordinates
@@ -76,11 +98,6 @@ public:
QObject* parent, ///< parent for newly allocated QGCQGeoCoordinates
QString& errorString); ///< returned error string if load failure
- /// Saves a QGeoCoordinate
- static void saveGeoCoordinate(const QGeoCoordinate& coordinate, ///< QGeoCoordinate to save
- bool writeAltitude, ///< true: write altitude to json
- QJsonValue& jsonValue); ///< json value to save to
-
/// Loads a list of QGeoCoordinates from a json array
/// @return false: validation failed
static bool loadGeoCoordinateArray(const QJsonValue& jsonValue, ///< json value which contains points
@@ -116,6 +133,15 @@ public:
private:
static QString _jsonValueTypeToString(QJsonValue::Type type);
+ static bool _loadGeoCoordinate(const QJsonValue& jsonValue,
+ bool altitudeRequired,
+ QGeoCoordinate& coordinate,
+ QString& errorString,
+ bool geoJsonFormat);
+ static void _saveGeoCoordinate(const QGeoCoordinate& coordinate,
+ bool writeAltitude,
+ QJsonValue& jsonValue,
+ bool geoJsonFormat);
static const char* _enumStringsJsonKey;
static const char* _enumValuesJsonKey;
diff --git a/src/MissionManager/AirMapManager.cc b/src/MissionManager/AirMapManager.cc
new file mode 100644
index 0000000000000000000000000000000000000000..d75772ab375ca72b4c1038e96b34547c32662439
--- /dev/null
+++ b/src/MissionManager/AirMapManager.cc
@@ -0,0 +1,981 @@
+/****************************************************************************
+ *
+ * (c) 2017 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#include "AirMapManager.h"
+#include "Vehicle.h"
+#include "QmlObjectListModel.h"
+#include "JsonHelper.h"
+#include "SettingsManager.h"
+#include "AppSettings.h"
+#include "AirMapSettings.h"
+#include "QGCQGeoCoordinate.h"
+#include "QGCApplication.h"
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+using namespace airmap;
+
+QGC_LOGGING_CATEGORY(AirMapManagerLog, "AirMapManagerLog")
+
+
+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="
+ < 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& 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 CircularAirspaceRestriction(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& 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 PolygonAirspaceRestriction(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: "<& 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 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 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 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 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 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 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 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);
+ }
+ });
+}
+
+
+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 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 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;
+ });
+}
+
+AirMapTrafficMonitor::~AirMapTrafficMonitor()
+{
+ stop();
+}
+
+void AirMapTrafficMonitor::startConnection(const QString& flightID)
+{
+ _flightID = flightID;
+ std::weak_ptr isAlive(_instance);
+ auto handler = [this, isAlive](const Traffic::Monitor::Result& result) {
+ if (!isAlive.lock()) return;
+ if (result) {
+ _monitor = result.value();
+ _subscriber = std::make_shared(
+ 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& 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();
+ }
+}
+
+AirMapManagerPerVehicle::AirMapManagerPerVehicle(AirMapSharedState& shared, const Vehicle& vehicle,
+ QGCToolbox& toolbox)
+ : AirspaceManagerPerVehicle(vehicle), _shared(shared),
+ _flightManager(shared), _telemetry(shared), _trafficMonitor(shared),
+ _toolbox(toolbox)
+{
+ connect(&_flightManager, &AirMapFlightManager::flightPermitStatusChanged,
+ this, &AirMapManagerPerVehicle::flightPermitStatusChanged);
+ connect(&_flightManager, &AirMapFlightManager::flightPermitStatusChanged,
+ this, &AirMapManagerPerVehicle::_flightPermitStatusChanged);
+ connect(&_flightManager, &AirMapFlightManager::error, this, &AirMapManagerPerVehicle::error);
+ connect(&_telemetry, &AirMapTelemetry::error, this, &AirMapManagerPerVehicle::error);
+ connect(&_trafficMonitor, &AirMapTrafficMonitor::error, this, &AirMapManagerPerVehicle::error);
+ connect(&_trafficMonitor, &AirMapTrafficMonitor::trafficUpdate, this, &AirspaceManagerPerVehicle::trafficUpdate);
+}
+
+void AirMapManagerPerVehicle::createFlight(const QList& missionItems)
+{
+ if (!_shared.client()) {
+ qCDebug(AirMapManagerLog) << "No AirMap client instance. Will not create a flight";
+ return;
+ }
+ _flightManager.createFlight(missionItems);
+}
+
+AirspaceAuthorization::PermitStatus AirMapManagerPerVehicle::flightPermitStatus() const
+{
+ return _flightManager.flightPermitStatus();
+}
+
+void AirMapManagerPerVehicle::startTelemetryStream()
+{
+ if (_flightManager.flightID() != "") {
+ _telemetry.startTelemetryStream(_flightManager.flightID());
+ }
+}
+
+void AirMapManagerPerVehicle::stopTelemetryStream()
+{
+ _telemetry.stopTelemetryStream();
+}
+
+bool AirMapManagerPerVehicle::isTelemetryStreaming() const
+{
+ return _telemetry.isTelemetryStreaming();
+}
+
+void AirMapManagerPerVehicle::endFlight()
+{
+ _flightManager.endFlight();
+ _trafficMonitor.stop();
+}
+
+void AirMapManagerPerVehicle::vehicleMavlinkMessageReceived(const mavlink_message_t& message)
+{
+ if (isTelemetryStreaming()) {
+ _telemetry.vehicleMavlinkMessageReceived(message);
+ }
+}
+
+void AirMapManagerPerVehicle::_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());
+ }
+}
+
+AirMapManager::AirMapManager(QGCApplication* app, QGCToolbox* toolbox)
+ : AirspaceManager(app, toolbox)
+{
+ _logger = std::make_shared();
+ qt::register_types(); // TODO: still needed?
+ _logger->logging_category().setEnabled(QtDebugMsg, true);
+ _logger->logging_category().setEnabled(QtInfoMsg, true);
+ _logger->logging_category().setEnabled(QtWarningMsg, true);
+ _dispatchingLogger = std::make_shared(_logger);
+
+ connect(&_shared, &AirMapSharedState::error, this, &AirMapManager::_error);
+}
+
+AirMapManager::~AirMapManager()
+{
+ if (_shared.client()) {
+ delete _shared.client();
+ }
+}
+
+void AirMapManager::setToolbox(QGCToolbox* toolbox)
+{
+ AirspaceManager::setToolbox(toolbox);
+ AirMapSettings* ap = toolbox->settingsManager()->airMapSettings();
+
+ connect(ap->apiKey(), &Fact::rawValueChanged, this, &AirMapManager::_settingsChanged);
+ connect(ap->clientID(), &Fact::rawValueChanged, this, &AirMapManager::_settingsChanged);
+ connect(ap->userName(), &Fact::rawValueChanged, this, &AirMapManager::_settingsChanged);
+ connect(ap->password(), &Fact::rawValueChanged, this, &AirMapManager::_settingsChanged);
+
+ _settingsChanged();
+
+}
+
+void AirMapManager::_error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails)
+{
+ qCDebug(AirMapManagerLog) << "Error: "<showMessage(QString("AirMap Error: %1. %2").arg(what).arg(airmapdMessage));
+}
+
+void AirMapManager::requestWeatherUpdate(const QGeoCoordinate& coordinate)
+{
+ if (!_shared.client()) {
+ qCDebug(AirMapManagerLog) << "No AirMap client instance. Not updating Weather information";
+ emit weatherUpdate(false, QGeoCoordinate{}, WeatherInformation{});
+ return;
+ }
+
+ Status::GetStatus::Parameters params;
+ params.longitude = coordinate.longitude();
+ params.latitude = coordinate.latitude();
+ params.weather = true;
+
+ _shared.client()->status().get_status_by_point(params, [this, coordinate](const Status::GetStatus::Result& result) {
+
+ if (result) {
+
+ const Status::Weather& weather = result.value().weather;
+ WeatherInformation weatherUpdateInfo;
+
+ weatherUpdateInfo.condition = QString::fromStdString(weather.condition);
+ weatherUpdateInfo.icon = QString::fromStdString(weather.icon);
+ weatherUpdateInfo.windHeading = weather.wind.heading;
+ weatherUpdateInfo.windSpeed = weather.wind.speed;
+ weatherUpdateInfo.windGusting = weather.wind.gusting;
+ weatherUpdateInfo.temperature = weather.temperature;
+ weatherUpdateInfo.humidity = weather.humidity;
+ weatherUpdateInfo.visibility = weather.visibility;
+ weatherUpdateInfo.precipitation = weather.precipitation;
+ emit weatherUpdate(true, coordinate, weatherUpdateInfo);
+
+ } else {
+ emit weatherUpdate(false, coordinate, WeatherInformation{});
+ }
+ });
+
+}
+
+void AirMapManager::_settingsChanged()
+{
+ qCDebug(AirMapManagerLog) << "AirMap settings changed";
+
+ AirMapSettings* ap = _toolbox->settingsManager()->airMapSettings();
+
+ AirMapSharedState::Settings settings;
+ settings.apiKey = ap->apiKey()->rawValueString();
+ bool apiKeyChanged = settings.apiKey != _shared.settings().apiKey;
+ settings.clientID = ap->clientID()->rawValueString();
+ settings.userName = ap->userName()->rawValueString();
+ settings.password = ap->password()->rawValueString();
+ _shared.setSettings(settings);
+
+ // need to re-create the client if the API key changed
+ if (_shared.client() && apiKeyChanged) {
+ delete _shared.client();
+ _shared.setClient(nullptr);
+ }
+
+
+ if (!_shared.client() && settings.apiKey != "") {
+ qCDebug(AirMapManagerLog) << "Creating AirMap client";
+
+ auto credentials = Credentials{};
+ credentials.api_key = _shared.settings().apiKey.toStdString();
+ auto configuration = Client::default_staging_configuration(credentials);
+ qt::Client::create(configuration, _dispatchingLogger, this, [this, ap](const qt::Client::CreateResult& result) {
+ if (result) {
+ qCDebug(AirMapManagerLog) << "Successfully created airmap::qt::Client instance";
+ _shared.setClient(result.value());
+
+ } else {
+ qWarning("Failed to create airmap::qt::Client instance");
+ QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : "");
+ _error("Failed to create airmap::qt::Client instance",
+ QString::fromStdString(result.error().message()), description);
+ }
+ });
+ }
+}
+
+AirspaceManagerPerVehicle* AirMapManager::instantiateVehicle(const Vehicle& vehicle)
+{
+ AirMapManagerPerVehicle* manager = new AirMapManagerPerVehicle(_shared, vehicle, *_toolbox);
+ connect(manager, &AirMapManagerPerVehicle::error, this, &AirMapManager::_error);
+ return manager;
+}
+
+AirspaceRestrictionProvider* AirMapManager::instantiateRestrictionProvider()
+{
+ AirMapRestrictionManager* restrictionManager = new AirMapRestrictionManager(_shared);
+ connect(restrictionManager, &AirMapRestrictionManager::error, this, &AirMapManager::_error);
+ return restrictionManager;
+}
+
diff --git a/src/MissionManager/AirMapManager.h b/src/MissionManager/AirMapManager.h
new file mode 100644
index 0000000000000000000000000000000000000000..99f85ee53a2a1a9b7b5db5d4e4e18a37d67bab05
--- /dev/null
+++ b/src/MissionManager/AirMapManager.h
@@ -0,0 +1,367 @@
+/****************************************************************************
+ *
+ * (c) 2017 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+#include "QGCToolbox.h"
+#include "QGCLoggingCategory.h"
+#include "QmlObjectListModel.h"
+#include "MissionItem.h"
+#include "MultiVehicleManager.h"
+#include "AirspaceManagement.h"
+
+#include
+#include
+#include
+#include
+
+#include
+#include
+#include
+
+#include
+#include
+#include
+#include
+
+Q_DECLARE_LOGGING_CATEGORY(AirMapManagerLog)
+
+
+/**
+ * @class LifetimeChecker
+ * Base class which helps to check if an object instance still exists.
+ * A subclass can take a weak pointer from _instance and then check if the object was deleted.
+ * This is used in callbacks that access 'this', but the instance might already be deleted (e.g. vehicle disconnect).
+ */
+class LifetimeChecker
+{
+public:
+ LifetimeChecker() : _instance(this, [](void*){}) { }
+ virtual ~LifetimeChecker() = default;
+
+protected:
+ std::shared_ptr _instance;
+};
+
+/**
+ * @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;
+
+ /**
+ * 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 _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& list);
+
+ 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& 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 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& update);
+
+private:
+ QString _flightID;
+ AirMapSharedState& _shared;
+ std::shared_ptr _monitor;
+ std::shared_ptr _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& 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
+{
+ Q_OBJECT
+
+public:
+ AirMapManager(QGCApplication* app, QGCToolbox* toolbox);
+ virtual ~AirMapManager();
+
+ void setToolbox(QGCToolbox* toolbox) override;
+
+ AirspaceManagerPerVehicle* instantiateVehicle(const Vehicle& vehicle) override;
+
+ AirspaceRestrictionProvider* instantiateRestrictionProvider() override;
+
+ QString name() const override { return "AirMap"; }
+
+ void requestWeatherUpdate(const QGeoCoordinate& coordinate) override;
+
+private slots:
+ void _error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
+
+ void _settingsChanged();
+private:
+
+ AirMapSharedState _shared;
+
+ std::shared_ptr _logger;
+ std::shared_ptr _dispatchingLogger;
+};
+
+
diff --git a/src/MissionManager/AirspaceController.cc b/src/MissionManager/AirspaceController.cc
new file mode 100644
index 0000000000000000000000000000000000000000..d81d76301408a86bb3bc470ed428471a78fe7898
--- /dev/null
+++ b/src/MissionManager/AirspaceController.cc
@@ -0,0 +1,20 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#include "AirspaceController.h"
+#include "AirspaceManagement.h"
+#include "QGCApplication.h"
+#include "QGCQGeoCoordinate.h"
+
+AirspaceController::AirspaceController(QObject* parent)
+ : QObject(parent)
+ , _manager(qgcApp()->toolbox()->airspaceManager())
+{
+}
+
diff --git a/src/MissionManager/AirspaceController.h b/src/MissionManager/AirspaceController.h
new file mode 100644
index 0000000000000000000000000000000000000000..b97c6a86a530dc3123efe493c220eb14d76a93c4
--- /dev/null
+++ b/src/MissionManager/AirspaceController.h
@@ -0,0 +1,36 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * 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_INVOKABLE void setROI(QGeoCoordinate center, double radius) { _manager->setROI(center, radius); }
+
+ QmlObjectListModel* polygons() { return _manager->polygonRestrictions(); }
+ QmlObjectListModel* circles() { return _manager->circularRestrictions(); }
+
+ Q_PROPERTY(QString providerName READ providerName CONSTANT)
+
+ QString providerName() { return _manager->name(); }
+private:
+ AirspaceManager* _manager;
+};
diff --git a/src/MissionManager/AirspaceManagement.cc b/src/MissionManager/AirspaceManagement.cc
new file mode 100644
index 0000000000000000000000000000000000000000..6b0aa1d9d4e3631eac53367de1383ed4b09c6d00
--- /dev/null
+++ b/src/MissionManager/AirspaceManagement.cc
@@ -0,0 +1,121 @@
+/****************************************************************************
+ *
+ * (c) 2017 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+
+#include "AirspaceManagement.h"
+#include
+
+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)
+{
+ _roiUpdateTimer.setInterval(2000);
+ _roiUpdateTimer.setSingleShot(true);
+ connect(&_roiUpdateTimer, &QTimer::timeout, this, &AirspaceManager::_updateToROI);
+ qmlRegisterUncreatableType("QGroundControl", 1, 0, "AirspaceAuthorization", "Reference only");
+ qRegisterMetaType();
+}
+
+AirspaceManager::~AirspaceManager()
+{
+ if (_restrictionsProvider) {
+ delete _restrictionsProvider;
+ }
+ _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);
+ }
+}
+
+void AirspaceManager::setROI(const QGeoCoordinate& center, double radiusMeters)
+{
+ _roiCenter = center;
+ _roiRadius = radiusMeters;
+ _roiUpdateTimer.start();
+}
+
+void AirspaceManager::_updateToROI()
+{
+ if (_restrictionsProvider) {
+ _restrictionsProvider->setROI(_roiCenter, _roiRadius);
+ }
+}
+
+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?
+ }
+}
+
+
+AirspaceManagerPerVehicle::AirspaceManagerPerVehicle(const Vehicle& vehicle)
+ : _vehicle(vehicle)
+{
+ connect(&_vehicle, &Vehicle::armedChanged, this, &AirspaceManagerPerVehicle::_vehicleArmedChanged);
+ connect(&_vehicle, &Vehicle::mavlinkMessageReceived, this, &AirspaceManagerPerVehicle::vehicleMavlinkMessageReceived);
+}
+
+void AirspaceManagerPerVehicle::_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();
+ }
+ }
+}
+
diff --git a/src/MissionManager/AirspaceManagement.h b/src/MissionManager/AirspaceManagement.h
new file mode 100644
index 0000000000000000000000000000000000000000..1a17b6ec496c428f3cfcad775c4bd61a5da549c0
--- /dev/null
+++ b/src/MissionManager/AirspaceManagement.h
@@ -0,0 +1,255 @@
+/****************************************************************************
+ *
+ * (c) 2017 QGROUNDCONTROL PROJECT
+ *
+ * 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
+#include
+#include
+
+#include
+
+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& polygons() const { return _polygonList; }
+ const QList& circles() const { return _circleList; }
+
+signals:
+ void requestDone(bool success);
+
+protected:
+ QList _polygonList;
+ QList _circleList;
+};
+
+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;
+
+ /**
+ * 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
+
+ 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& 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
+};
diff --git a/src/MissionManager/GeoFenceManager.cc b/src/MissionManager/GeoFenceManager.cc
index ce6ce1933efecfbc1ef788047a598f12afcf245e..ddda1d1bd6567777a964e79564d9be14d860f729 100644
--- a/src/MissionManager/GeoFenceManager.cc
+++ b/src/MissionManager/GeoFenceManager.cc
@@ -11,6 +11,7 @@
#include "Vehicle.h"
#include "QmlObjectListModel.h"
#include "ParameterManager.h"
+#include "QGCApplication.h"
#include "QGCMapPolygon.h"
#include "QGCMapCircle.h"
@@ -20,6 +21,7 @@ GeoFenceManager::GeoFenceManager(Vehicle* vehicle)
: _vehicle (vehicle)
, _planManager (vehicle, MAV_MISSION_TYPE_FENCE)
, _firstParamLoadComplete (false)
+ , _airspaceManager (qgcApp()->toolbox()->airspaceManager())
{
connect(&_planManager, &PlanManager::inProgressChanged, this, &GeoFenceManager::inProgressChanged);
connect(&_planManager, &PlanManager::error, this, &GeoFenceManager::error);
diff --git a/src/MissionManager/GeoFenceManager.h b/src/MissionManager/GeoFenceManager.h
index 9c7c4e41fd31cdf3d415e6932da8041a7a9e6054..26ec69d968f7c8ef525fb4249ab1766a27694c6e 100644
--- a/src/MissionManager/GeoFenceManager.h
+++ b/src/MissionManager/GeoFenceManager.h
@@ -13,6 +13,7 @@
#include
#include
+#include "AirspaceManagement.h"
#include "QGCLoggingCategory.h"
#include "FactSystem.h"
#include "PlanManager.h"
@@ -96,6 +97,7 @@ private:
bool _firstParamLoadComplete;
QList _sendPolygons;
QList _sendCircles;
+ AirspaceManager* _airspaceManager;
};
#endif
diff --git a/src/MissionManager/PlanManager.cc b/src/MissionManager/PlanManager.cc
index 33a609f5dc444389b89f5f5198bb9cc3207c87db..c73286c8765543241c17fd2a2276e55a25e2fc55 100644
--- a/src/MissionManager/PlanManager.cc
+++ b/src/MissionManager/PlanManager.cc
@@ -78,6 +78,14 @@ void PlanManager::writeMissionItems(const QList& missionItems)
return;
}
+ if (_planType == MAV_MISSION_TYPE_MISSION) {
+ // upload the flight to the airspace management backend
+ AirspaceManagerPerVehicle* airspaceManager = _vehicle->airspaceManager();
+ if (airspaceManager) {
+ airspaceManager->createFlight(missionItems);
+ }
+ }
+
_clearAndDeleteWriteMissionItems();
bool skipFirstItem = _planType == MAV_MISSION_TYPE_MISSION && !_vehicle->firmwarePlugin()->sendHomePositionToVehicle();
diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc
index ec3d865182f5c6a34c42ab8291559ce7dfa4816f..832fadb429dd23c997c75332dee2fb5c1960c66c 100644
--- a/src/QGCApplication.cc
+++ b/src/QGCApplication.cc
@@ -84,6 +84,7 @@
#include "CameraCalc.h"
#include "VisualMissionItem.h"
#include "EditPositionDialogController.h"
+#include "AirspaceController.h"
#ifndef NO_SERIAL_LINK
#include "SerialLink.h"
@@ -373,6 +374,7 @@ void QGCApplication::_initCommon(void)
qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "ParameterManager", "Reference only");
qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "QGCCameraManager", "Reference only");
qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "QGCCameraControl", "Reference only");
+ qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "AirspaceController", "Reference only");
qmlRegisterUncreatableType ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only");
qmlRegisterUncreatableType ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only");
qmlRegisterUncreatableType ("QGroundControl.QGCPositionManager", 1, 0, "QGCPositionManager", "Reference only");
diff --git a/src/QGCToolbox.cc b/src/QGCToolbox.cc
index c2eadcfd9dcbefcbcc74824d9439a263b10d81ed..94d5795a31f304ceed27249573972a8536a722b0 100644
--- a/src/QGCToolbox.cc
+++ b/src/QGCToolbox.cc
@@ -30,32 +30,34 @@
#include "QGCOptions.h"
#include "SettingsManager.h"
#include "QGCApplication.h"
+#include "AirMapManager.h"
#if defined(QGC_CUSTOM_BUILD)
#include CUSTOMHEADER
#endif
QGCToolbox::QGCToolbox(QGCApplication* app)
- : _audioOutput(NULL)
- , _factSystem(NULL)
+ : _audioOutput (NULL)
+ , _factSystem (NULL)
, _firmwarePluginManager(NULL)
#ifndef __mobile__
- , _gpsManager(NULL)
+ , _gpsManager (NULL)
#endif
- , _imageProvider(NULL)
- , _joystickManager(NULL)
- , _linkManager(NULL)
- , _mavlinkProtocol(NULL)
- , _missionCommandTree(NULL)
- , _multiVehicleManager(NULL)
- , _mapEngineManager(NULL)
- , _uasMessageHandler(NULL)
- , _followMe(NULL)
- , _qgcPositionManager(NULL)
- , _videoManager(NULL)
- , _mavlinkLogManager(NULL)
- , _corePlugin(NULL)
- , _settingsManager(NULL)
+ , _imageProvider (NULL)
+ , _joystickManager (NULL)
+ , _linkManager (NULL)
+ , _mavlinkProtocol (NULL)
+ , _missionCommandTree (NULL)
+ , _multiVehicleManager (NULL)
+ , _mapEngineManager (NULL)
+ , _uasMessageHandler (NULL)
+ , _followMe (NULL)
+ , _qgcPositionManager (NULL)
+ , _videoManager (NULL)
+ , _mavlinkLogManager (NULL)
+ , _corePlugin (NULL)
+ , _settingsManager (NULL)
+ , _airspaceManager (NULL)
{
// SettingsManager must be first so settings are available to any subsequent tools
_settingsManager = new SettingsManager(app, this);
@@ -80,6 +82,7 @@ QGCToolbox::QGCToolbox(QGCApplication* app)
_followMe = new FollowMe (app, this);
_videoManager = new VideoManager (app, this);
_mavlinkLogManager = new MAVLinkLogManager (app, this);
+ _airspaceManager = new AirMapManager (app, this);
}
void QGCToolbox::setChildToolboxes(void)
@@ -106,6 +109,7 @@ void QGCToolbox::setChildToolboxes(void)
_qgcPositionManager->setToolbox(this);
_videoManager->setToolbox(this);
_mavlinkLogManager->setToolbox(this);
+ _airspaceManager->setToolbox(this);
}
void QGCToolbox::_scanAndLoadPlugins(QGCApplication* app)
diff --git a/src/QGCToolbox.h b/src/QGCToolbox.h
index a45e37eb473f1ab8b6aaac9a3fb10508c2da8b6d..5ece9befe85c08d488cf656586c6e4e668ab3462 100644
--- a/src/QGCToolbox.h
+++ b/src/QGCToolbox.h
@@ -32,6 +32,7 @@ class VideoManager;
class MAVLinkLogManager;
class QGCCorePlugin;
class SettingsManager;
+class AirspaceManager;
/// This is used to manage all of our top level services/tools
class QGCToolbox : public QObject {
@@ -56,6 +57,7 @@ public:
MAVLinkLogManager* mavlinkLogManager(void) { return _mavlinkLogManager; }
QGCCorePlugin* corePlugin(void) { return _corePlugin; }
SettingsManager* settingsManager(void) { return _settingsManager; }
+ AirspaceManager* airspaceManager(void) { return _airspaceManager; }
#ifndef __mobile__
GPSManager* gpsManager(void) { return _gpsManager; }
@@ -86,6 +88,7 @@ private:
MAVLinkLogManager* _mavlinkLogManager;
QGCCorePlugin* _corePlugin;
SettingsManager* _settingsManager;
+ AirspaceManager* _airspaceManager;
friend class QGCApplication;
};
diff --git a/src/Settings/AirMap.SettingsGroup.json b/src/Settings/AirMap.SettingsGroup.json
new file mode 100644
index 0000000000000000000000000000000000000000..5806903ae0445c06c8f65496769a1b56b23db052
--- /dev/null
+++ b/src/Settings/AirMap.SettingsGroup.json
@@ -0,0 +1,26 @@
+[
+{
+ "name": "apiKey",
+ "shortDescription": "AirMap API Key",
+ "type": "string",
+ "defaultValue": ""
+},
+{
+ "name": "clientID",
+ "shortDescription": "AirMap Client ID",
+ "type": "string",
+ "defaultValue": ""
+},
+{
+ "name": "userName",
+ "shortDescription": "AirMap User Name",
+ "type": "string",
+ "defaultValue": ""
+},
+{
+ "name": "password",
+ "shortDescription": "AirMap Password",
+ "type": "string",
+ "defaultValue": ""
+}
+]
diff --git a/src/Settings/AirMapSettings.cc b/src/Settings/AirMapSettings.cc
new file mode 100644
index 0000000000000000000000000000000000000000..a2cc7ce0ea48f0a7f500b1b13311d8c414dd093a
--- /dev/null
+++ b/src/Settings/AirMapSettings.cc
@@ -0,0 +1,30 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#include "AirMapSettings.h"
+#include "QGCPalette.h"
+#include "QGCApplication.h"
+
+#include
+#include
+
+DECLARE_SETTINGGROUP(AirMap)
+{
+ INIT_SETTINGFACT(apiKey);
+ INIT_SETTINGFACT(clientID);
+ INIT_SETTINGFACT(userName);
+ INIT_SETTINGFACT(password);
+ QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
+ qmlRegisterUncreatableType("QGroundControl.SettingsManager", 1, 0, "AirMapSettings", "Reference only");
+}
+
+DECLARE_SETTINGSFACT(AirMapSettings, apiKey)
+DECLARE_SETTINGSFACT(AirMapSettings, clientID)
+DECLARE_SETTINGSFACT(AirMapSettings, userName)
+DECLARE_SETTINGSFACT(AirMapSettings, password)
diff --git a/src/Settings/AirMapSettings.h b/src/Settings/AirMapSettings.h
new file mode 100644
index 0000000000000000000000000000000000000000..04542d52d76a85a54b93decc510ad775ecb9595a
--- /dev/null
+++ b/src/Settings/AirMapSettings.h
@@ -0,0 +1,28 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+#include "SettingsGroup.h"
+#include "QGCMAVLink.h"
+
+class AirMapSettings : public SettingsGroup
+{
+ Q_OBJECT
+public:
+ AirMapSettings(QObject* parent = NULL);
+
+ DEFINE_SETTINGGROUP(AirMap)
+
+ DEFINE_SETTINGFACT(apiKey)
+ DEFINE_SETTINGFACT(clientID)
+ DEFINE_SETTINGFACT(userName)
+ DEFINE_SETTINGFACT(password)
+
+};
diff --git a/src/Settings/SettingsGroup.h b/src/Settings/SettingsGroup.h
index 048c0b1132fdb721cb48c5f962ad505776f2c934..7f0bfce022a0d9155b9530a520ec593f761ad56e 100644
--- a/src/Settings/SettingsGroup.h
+++ b/src/Settings/SettingsGroup.h
@@ -17,6 +17,34 @@
#include
+#define DEFINE_SETTINGGROUP(CLASS) \
+ static const char* CLASS ## Settings ## GroupName;
+
+#define DECLARE_SETTINGGROUP(CLASS) \
+ const char* CLASS ## Settings::CLASS ## Settings ## GroupName = #CLASS; \
+ CLASS ## Settings::CLASS ## Settings(QObject* parent) \
+ : SettingsGroup(CLASS ## Settings ## GroupName, QString() /* root settings group */, parent)
+
+#define DECLARE_SETTINGSFACT(CLASS, NAME) \
+ const char* CLASS::NAME ## Name = #NAME; \
+ Fact* CLASS::NAME(void) \
+ { \
+ if (!_ ## NAME ## Fact) { \
+ _ ## NAME ## Fact = _createSettingsFact(NAME ## Name); \
+ } \
+ return _ ## NAME ## Fact; \
+ }
+
+#define DEFINE_SETTINGFACT(NAME) \
+ public: \
+ Q_PROPERTY(Fact* NAME READ NAME CONSTANT) \
+ Fact* NAME(); \
+ static const char* NAME ## Name; \
+ private: \
+ SettingsFact* _ ## NAME ## Fact;
+
+#define INIT_SETTINGFACT(NAME) _ ## NAME ## Fact = NULL
+
/// Provides access to group of settings. The group is named and has a visible property associated with which can control whether the group
/// is shows in the ui.
class SettingsGroup : public QObject
diff --git a/src/Settings/SettingsManager.cc b/src/Settings/SettingsManager.cc
index 643bf234515342e8b52af8e66fbe829e8907723d..b7d6a127bb6b4129139d6a906fb73a63c3c72421 100644
--- a/src/Settings/SettingsManager.cc
+++ b/src/Settings/SettingsManager.cc
@@ -14,6 +14,7 @@
SettingsManager::SettingsManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
+ , _airMapSettings (NULL)
, _appSettings (NULL)
, _unitsSettings (NULL)
, _autoConnectSettings (NULL)
@@ -40,4 +41,5 @@ void SettingsManager::setToolbox(QGCToolbox *toolbox)
_rtkSettings = new RTKSettings(this);
_guidedSettings = new GuidedSettings(this);
_brandImageSettings = new BrandImageSettings(this);
+ _airMapSettings = new AirMapSettings(this);
}
diff --git a/src/Settings/SettingsManager.h b/src/Settings/SettingsManager.h
index a69b7f6bc55fcb7eec112da77aeaa0d7322a6c59..bba1104e797b27294960d98488f696be7d8875b9 100644
--- a/src/Settings/SettingsManager.h
+++ b/src/Settings/SettingsManager.h
@@ -22,6 +22,7 @@
#include "RTKSettings.h"
#include "GuidedSettings.h"
#include "BrandImageSettings.h"
+#include "AirMapSettings.h"
#include
@@ -33,6 +34,7 @@ class SettingsManager : public QGCTool
public:
SettingsManager(QGCApplication* app, QGCToolbox* toolbox);
+ Q_PROPERTY(QObject* airMapSettings READ airMapSettings CONSTANT)
Q_PROPERTY(QObject* appSettings READ appSettings CONSTANT)
Q_PROPERTY(QObject* unitsSettings READ unitsSettings CONSTANT)
Q_PROPERTY(QObject* autoConnectSettings READ autoConnectSettings CONSTANT)
@@ -45,6 +47,7 @@ public:
// Override from QGCTool
virtual void setToolbox(QGCToolbox *toolbox);
+ AirMapSettings* airMapSettings (void) { return _airMapSettings; }
AppSettings* appSettings (void) { return _appSettings; }
UnitsSettings* unitsSettings (void) { return _unitsSettings; }
AutoConnectSettings* autoConnectSettings (void) { return _autoConnectSettings; }
@@ -55,6 +58,7 @@ public:
BrandImageSettings* brandImageSettings (void) { return _brandImageSettings; }
private:
+ AirMapSettings* _airMapSettings;
AppSettings* _appSettings;
UnitsSettings* _unitsSettings;
AutoConnectSettings* _autoConnectSettings;
diff --git a/src/Vehicle/ADSBVehicle.cc b/src/Vehicle/ADSBVehicle.cc
index bd796cf0bc7d942abc2f1ce5978d17005cc5e449..6fcda9ef0eedb04f0223b2553232959710279ed9 100644
--- a/src/Vehicle/ADSBVehicle.cc
+++ b/src/Vehicle/ADSBVehicle.cc
@@ -27,6 +27,23 @@ ADSBVehicle::ADSBVehicle(mavlink_adsb_vehicle_t& adsbVehicle, QObject* parent)
update(adsbVehicle);
}
+ADSBVehicle::ADSBVehicle(const QGeoCoordinate& location, float heading, QObject* parent)
+ : QObject(parent), _icaoAddress(0)
+{
+ update(location, heading);
+}
+
+void ADSBVehicle::update(const QGeoCoordinate& location, float heading)
+{
+ _coordinate = location;
+ _altitude = location.altitude();
+ _heading = heading;
+ emit coordinateChanged(_coordinate);
+ emit altitudeChanged(_altitude);
+ emit headingChanged(_heading);
+ _lastUpdateTimer.restart();
+}
+
void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle)
{
if (_icaoAddress != adsbVehicle.ICAO_address) {
@@ -68,4 +85,10 @@ void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle)
_heading = newHeading;
emit headingChanged(_heading);
}
+ _lastUpdateTimer.restart();
+}
+
+bool ADSBVehicle::expired()
+{
+ return _lastUpdateTimer.hasExpired(expirationTimeoutMs);
}
diff --git a/src/Vehicle/ADSBVehicle.h b/src/Vehicle/ADSBVehicle.h
index fe6046fc1515118e101f181ad3d33cd571d0b997..f0124f089bd69cefe68cbfd662fe894099a3e9eb 100644
--- a/src/Vehicle/ADSBVehicle.h
+++ b/src/Vehicle/ADSBVehicle.h
@@ -11,6 +11,7 @@
#include
#include
+#include
#include "QGCMAVLink.h"
@@ -21,6 +22,8 @@ class ADSBVehicle : public QObject
public:
ADSBVehicle(mavlink_adsb_vehicle_t& adsbVehicle, QObject* parent = NULL);
+ ADSBVehicle(const QGeoCoordinate& location, float heading, QObject* parent = NULL);
+
Q_PROPERTY(int icaoAddress READ icaoAddress CONSTANT)
Q_PROPERTY(QString callsign READ callsign NOTIFY callsignChanged)
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate NOTIFY coordinateChanged)
@@ -36,6 +39,11 @@ public:
/// Update the vehicle with new information
void update(mavlink_adsb_vehicle_t& adsbVehicle);
+ void update(const QGeoCoordinate& location, float heading);
+
+ /// check if the vehicle is expired and should be removed
+ bool expired();
+
signals:
void coordinateChanged(QGeoCoordinate coordinate);
void callsignChanged(QString callsign);
@@ -43,9 +51,14 @@ signals:
void headingChanged(double heading);
private:
+ static constexpr qint64 expirationTimeoutMs = 5000; ///< timeout with no update in ms after which the vehicle is removed.
+ ///< AirMap sends updates for each vehicle every second.
+
uint32_t _icaoAddress;
QString _callsign;
QGeoCoordinate _coordinate;
double _altitude;
double _heading;
+
+ QElapsedTimer _lastUpdateTimer;
};
diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc
index 64e27fa4774ce233995443e142a46f2415fa3102..de687093d7491d7f24d229aea27e5f187c5e4f5c 100644
--- a/src/Vehicle/Vehicle.cc
+++ b/src/Vehicle/Vehicle.cc
@@ -38,6 +38,7 @@
#include "QGCCameraManager.h"
#include "VideoReceiver.h"
#include "VideoManager.h"
+#include "AirspaceController.h"
QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")
@@ -139,6 +140,8 @@ Vehicle::Vehicle(LinkInterface* link,
, _rallyPointManager(NULL)
, _rallyPointManagerInitialRequestSent(false)
, _parameterManager(NULL)
+ , _airspaceController(NULL)
+ , _airspaceManagerPerVehicle(NULL)
, _armed(false)
, _base_mode(0)
, _custom_mode(0)
@@ -257,6 +260,22 @@ Vehicle::Vehicle(LinkInterface* link,
// Create camera manager instance
_cameras = _firmwarePlugin->createCameraManager(this);
emit dynamicCamerasChanged();
+
+ connect(&_adsbTimer, &QTimer::timeout, this, &Vehicle::_adsbTimerTimeout);
+ _adsbTimer.setSingleShot(false);
+ _adsbTimer.start(1000);
+
+ _airspaceController = new AirspaceController(this);
+
+ AirspaceManager* airspaceManager = _toolbox->airspaceManager();
+ if (airspaceManager) {
+ _airspaceManagerPerVehicle = airspaceManager->instantiateVehicle(*this);
+ if (_airspaceManagerPerVehicle) {
+ connect(_airspaceManagerPerVehicle, &AirspaceManagerPerVehicle::trafficUpdate, this, &Vehicle::_trafficUpdate);
+ connect(_airspaceManagerPerVehicle, &AirspaceManagerPerVehicle::flightPermitStatusChanged, this, &Vehicle::flightPermitStatusChanged);
+ }
+ }
+
}
// Disconnected Vehicle for offline editing
@@ -317,6 +336,8 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _rallyPointManager(NULL)
, _rallyPointManagerInitialRequestSent(false)
, _parameterManager(NULL)
+ , _airspaceController(NULL)
+ , _airspaceManagerPerVehicle(NULL)
, _armed(false)
, _base_mode(0)
, _custom_mode(0)
@@ -450,6 +471,9 @@ Vehicle::~Vehicle()
delete _mav;
_mav = NULL;
+ if (_airspaceManagerPerVehicle) {
+ delete _airspaceManagerPerVehicle;
+ }
}
void Vehicle::prepareDelete()
@@ -2978,6 +3002,35 @@ void Vehicle::_updateHighLatencyLink(void)
}
}
+void Vehicle::_trafficUpdate(QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading)
+{
+ Q_UNUSED(vehicle_id);
+ // qDebug() << "traffic update:" << traffic_id << vehicle_id << heading << location;
+ // TODO: filter based on minimum altitude?
+ if (_trafficVehicleMap.contains(traffic_id)) {
+ _trafficVehicleMap[traffic_id]->update(location, heading);
+ } else {
+ ADSBVehicle* vehicle = new ADSBVehicle(location, heading, this);
+ _trafficVehicleMap[traffic_id] = vehicle;
+ _adsbVehicles.append(vehicle);
+ }
+
+}
+void Vehicle::_adsbTimerTimeout()
+{
+ // TODO: take into account _adsbICAOMap as well? Needs to be tested, especially the timeout
+
+ for (auto it = _trafficVehicleMap.begin(); it != _trafficVehicleMap.end();) {
+ if (it.value()->expired()) {
+ _adsbVehicles.removeOne(it.value());
+ delete it.value();
+ it = _trafficVehicleMap.erase(it);
+ } else {
+ ++it;
+ }
+ }
+}
+
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h
index 8159e2c4ea99f0ccaeff53b494ce01c2ca3f9ab7..e1225e2cd897ce041453240662e9c17120fd873a 100644
--- a/src/Vehicle/Vehicle.h
+++ b/src/Vehicle/Vehicle.h
@@ -20,6 +20,7 @@
#include "MAVLinkProtocol.h"
#include "UASMessageHandler.h"
#include "SettingsFact.h"
+#include
class UAS;
class UASInterface;
@@ -35,6 +36,7 @@ class UASMessage;
class SettingsManager;
class ADSBVehicle;
class QGCCameraManager;
+class AirspaceController;
Q_DECLARE_LOGGING_CATEGORY(VehicleLog)
@@ -353,6 +355,8 @@ public:
Q_PROPERTY(QString hobbsMeter READ hobbsMeter NOTIFY hobbsMeterChanged)
Q_PROPERTY(bool vtolInFwdFlight READ vtolInFwdFlight WRITE setVtolInFwdFlight NOTIFY vtolInFwdFlightChanged)
Q_PROPERTY(bool highLatencyLink READ highLatencyLink NOTIFY highLatencyLinkChanged)
+ Q_PROPERTY(AirspaceAuthorization::PermitStatus flightPermitStatus READ flightPermitStatus NOTIFY flightPermitStatusChanged) ///< state of flight permission
+ Q_PROPERTY(AirspaceController* airspaceController READ airspaceController CONSTANT)
// Vehicle state used for guided control
Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged) ///< Vehicle is flying
@@ -572,6 +576,8 @@ public:
QmlObjectListModel* cameraTriggerPoints(void) { return &_cameraTriggerPoints; }
QmlObjectListModel* adsbVehicles(void) { return &_adsbVehicles; }
+ AirspaceController* airspaceController() { return _airspaceController; }
+
int flowImageIndex() { return _flowImageIndex; }
//-- Mavlink Logging
@@ -755,6 +761,11 @@ public:
/// Vehicle is about to be deleted
void prepareDelete();
+ AirspaceAuthorization::PermitStatus flightPermitStatus() const
+ { return _airspaceManagerPerVehicle ? _airspaceManagerPerVehicle->flightPermitStatus() : AirspaceAuthorization::PermitUnknown; }
+
+ AirspaceManagerPerVehicle* airspaceManager() const { return _airspaceManagerPerVehicle; }
+
signals:
void allLinksInactive(Vehicle* vehicle);
void coordinateChanged(QGeoCoordinate coordinate);
@@ -789,6 +800,8 @@ signals:
void capabilityBitsChanged(uint64_t capabilityBits);
void toolBarIndicatorsChanged(void);
void highLatencyLinkChanged(bool highLatencyLink);
+ void flightPermitStatusChanged();
+
void messagesReceivedChanged ();
void messagesSentChanged ();
@@ -887,6 +900,9 @@ private slots:
void _updateHobbsMeter(void);
void _vehicleParamLoaded(bool ready);
+ void _trafficUpdate(QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading);
+ void _adsbTimerTimeout();
+
private:
bool _containsLink(LinkInterface* link);
void _addLink(LinkInterface* link);
@@ -1037,7 +1053,10 @@ private:
RallyPointManager* _rallyPointManager;
bool _rallyPointManagerInitialRequestSent;
- ParameterManager* _parameterManager;
+ ParameterManager* _parameterManager;
+
+ AirspaceController* _airspaceController;
+ AirspaceManagerPerVehicle* _airspaceManagerPerVehicle;
bool _armed; ///< true: vehicle is armed
uint8_t _base_mode; ///< base_mode from HEARTBEAT
@@ -1068,6 +1087,8 @@ private:
QmlObjectListModel _adsbVehicles;
QMap _adsbICAOMap;
+ QMap _trafficVehicleMap;
+ QTimer _adsbTimer;
// Toolbox references
FirmwarePluginManager* _firmwarePluginManager;
diff --git a/src/ui/preferences/GeneralSettings.qml b/src/ui/preferences/GeneralSettings.qml
index e74cfe334f5cfb5fe4d05d06a2c5604a449a5b41..4a36ad9608269ea3ea66ec1c9d79de86ce80e186 100644
--- a/src/ui/preferences/GeneralSettings.qml
+++ b/src/ui/preferences/GeneralSettings.qml
@@ -555,6 +555,52 @@ QGCView {
}
}
+ //-----------------------------------------------------------------
+ //-- AirMap
+ Item {
+ width: _qgcView.width * 0.8
+ height: unitLabel.height
+ anchors.margins: ScreenTools.defaultFontPixelWidth
+ anchors.horizontalCenter: parent.horizontalCenter
+ visible: QGroundControl.settingsManager.rtkSettings.visible
+ QGCLabel {
+ text: qsTr("AirMap")
+ font.family: ScreenTools.demiboldFontFamily
+ }
+ }
+ Rectangle {
+ height: airMapCol.height + (ScreenTools.defaultFontPixelHeight * 2)
+ width: _qgcView.width * 0.8
+ color: qgcPal.windowShade
+ anchors.margins: ScreenTools.defaultFontPixelWidth
+ anchors.horizontalCenter: parent.horizontalCenter
+ visible: QGroundControl.settingsManager.airMapSettings.visible
+ Column {
+ id: airMapCol
+ spacing: ScreenTools.defaultFontPixelWidth
+ anchors.centerIn: parent
+ Row {
+ spacing: ScreenTools.defaultFontPixelWidth
+ QGCLabel {text: qsTr("API Key:"); width: _labelWidth; anchors.verticalCenter: parent.verticalCenter }
+ FactTextField {fact: QGroundControl.settingsManager.airMapSettings.apiKey; width: _editFieldWidth; anchors.verticalCenter: parent.verticalCenter }
+ }
+ Row {
+ spacing: ScreenTools.defaultFontPixelWidth
+ QGCLabel {text: qsTr("Client ID:"); width: _labelWidth; anchors.verticalCenter: parent.verticalCenter }
+ FactTextField {fact: QGroundControl.settingsManager.airMapSettings.clientID; width: _editFieldWidth; anchors.verticalCenter: parent.verticalCenter }
+ }
+ Row {
+ spacing: ScreenTools.defaultFontPixelWidth
+ QGCLabel {text: qsTr("User Name:"); width: _labelWidth; anchors.verticalCenter: parent.verticalCenter }
+ FactTextField {fact: QGroundControl.settingsManager.airMapSettings.userName; width: _editFieldWidth; anchors.verticalCenter: parent.verticalCenter }
+ }
+ Row {
+ spacing: ScreenTools.defaultFontPixelWidth
+ QGCLabel {text: qsTr("Password:"); width: _labelWidth; anchors.verticalCenter: parent.verticalCenter }
+ FactTextField {fact: QGroundControl.settingsManager.airMapSettings.password; width: _editFieldWidth; anchors.verticalCenter: parent.verticalCenter; echoMode: TextInput.Password }
+ }
+ }
+ }
//-----------------------------------------------------------------
//-- Video Source
Item {