Commit e8b37fc8 authored by Gus Grubba's avatar Gus Grubba

Merge branch 'AirMapWithAirmapd' into Airmap

* AirMapWithAirmapd: (33 commits)
  qgroundcontrol.pro: update build to latest airmapd master
  AirMapManager: update authorizations to changed airmapd interface
  rebase fixup: remove AirMapController.{cc,h}
  remove submodule commits qmqtt and tiny-AES128-C
  AirMapManager: error handling, change to updated API of airmapd
  AirMapManager: update polygons to changed airmapd interface
  AirMapManager: update flight search according to updated airmapd
  AirMap: remove SITA registration numbers
  AirspaceManagement & AirMapManager: add weather request API
  AirMapManager: add LifetimeChecker class to prevent callbacks from accessing invalid memory
  AirMapManager: handle multi_polygon
  AirMapManager: change backend to use airmapd
  AirMap: refactor for multi-vehicle support & base class API
  AirMap traffic: remove inactive vehicles after a timeout of 5 seconds
  AirMapManager: handle dynamic setting changes
  AirmapManager: make sure to pass the SITA reg data to the right objects
  Make AirMapController as part of a Vehicle rather than a creatable QML instance. This is ultimately linked to a vehicle and not the view. Eventually a lot of the code currently in AirMapManager will have to come here as well so the data persists with a vehicle. AirMapManager should only handle the global aspects. Added a temporary indicator right below the toolbar. It's only visible if a permission (of any kind) exists. I need to understand better how this works before coming up with a more permanent solution. Restored toolbar to its original state (brand logo and whatnot)
  Added include and lib path for protobuf on maxOS (we need to make this automatic for all builds) Added AirMap settings (SettingsGroup) Added AirMap settings block to General Settings Create macros to deal with the tedious repetitions within SettingsGroup Removed old, hacked in setting for AirMapKey Remove a few of the tons of build warnings
  PlanManager: upload flight to AirMap when uploading to the vehicle
  AirMapController: add flightPermitStatusChanged
  ...

# Conflicts:
#	src/QGCApplication.cc
#	src/Vehicle/Vehicle.cc
#	src/Vehicle/Vehicle.h
parents 191f9cae 96aa904b
......@@ -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)")
}
}
......@@ -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 \
......
......@@ -199,6 +199,7 @@
<file alias="MavCmdInfoRover.json">src/MissionManager/MavCmdInfoRover.json</file>
<file alias="MavCmdInfoSub.json">src/MissionManager/MavCmdInfoSub.json</file>
<file alias="MavCmdInfoVTOL.json">src/MissionManager/MavCmdInfoVTOL.json</file>
<file alias="AirMap.SettingsGroup.json">src/Settings/AirMap.SettingsGroup.json</file>
<file alias="App.SettingsGroup.json">src/Settings/App.SettingsGroup.json</file>
<file alias="AutoConnect.SettingsGroup.json">src/Settings/AutoConnect.SettingsGroup.json</file>
<file alias="FlightMap.SettingsGroup.json">src/Settings/FlightMap.SettingsGroup.json</file>
......
......@@ -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 : ""
}
}
......@@ -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
}
}
}
......@@ -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<QJsonValue::Type>& types, QString& errorString)
{
for (int i=0; i<types.count(); i++) {
......@@ -344,7 +385,7 @@ bool JsonHelper::loadPolygon(const QJsonArray& polygonArray, QmlObjectListModel&
const QJsonValue& pointValue = polygonArray[i];
QGeoCoordinate pointCoord;
if (!JsonHelper::loadGeoCoordinate(pointValue, false /* altitudeRequired */, pointCoord, errorString)) {
if (!JsonHelper::loadGeoCoordinate(pointValue, false /* altitudeRequired */, pointCoord, errorString, true)) {
list.clearAndDeleteContents();
return false;
}
......
......@@ -64,11 +64,33 @@ public:
static bool validateKeys(const QJsonObject& jsonObject, const QList<KeyValidateInfo>& 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;
......
This diff is collapsed.
This diff is collapsed.
/****************************************************************************
*
* (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 "AirspaceController.h"
#include "AirspaceManagement.h"
#include "QGCApplication.h"
#include "QGCQGeoCoordinate.h"
AirspaceController::AirspaceController(QObject* parent)
: QObject(parent)
, _manager(qgcApp()->toolbox()->airspaceManager())
{
}
/****************************************************************************
*
* (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_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;
};
/****************************************************************************
*
* (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")
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<AirspaceAuthorization>("QGroundControl", 1, 0, "AirspaceAuthorization", "Reference only");
qRegisterMetaType<WeatherInformation>();
}
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();
}
}
}
/****************************************************************************
*
* (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 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<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
};
......@@ -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);
......
......@@ -13,6 +13,7 @@
#include <QObject>
#include <QGeoCoordinate>
#include "AirspaceManagement.h"
#include "QGCLoggingCategory.h"
#include "FactSystem.h"
#include "PlanManager.h"
......@@ -96,6 +97,7 @@ private:
bool _firstParamLoadComplete;
QList<QGCFencePolygon> _sendPolygons;
QList<QGCFenceCircle> _sendCircles;
AirspaceManager* _airspaceManager;
};
#endif
......@@ -78,6 +78,14 @@ void PlanManager::writeMissionItems(const QList<MissionItem*>& 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();
......
......@@ -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<ParameterManager> ("QGroundControl.Vehicle", 1, 0, "ParameterManager", "Reference only");
qmlRegisterUncreatableType<QGCCameraManager> ("QGroundControl.Vehicle", 1, 0, "QGCCameraManager", "Reference only");
qmlRegisterUncreatableType<QGCCameraControl> ("QGroundControl.Vehicle", 1, 0, "QGCCameraControl", "Reference only");
qmlRegisterUncreatableType<AirspaceController> ("QGroundControl.Vehicle", 1, 0, "AirspaceController", "Reference only");
qmlRegisterUncreatableType<JoystickManager> ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only");
qmlRegisterUncreatableType<Joystick> ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only");
qmlRegisterUncreatableType<QGCPositionManager> ("QGroundControl.QGCPositionManager", 1, 0, "QGCPositionManager", "Reference only");
......
......@@ -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)
......
......@@ -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;
};
......
[
{
"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": ""
}
]
/****************************************************************************
*
* (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 "AirMapSettings.h"
#include "QGCPalette.h"
#include "QGCApplication.h"
#include <QQmlEngine>
#include <QtQml>
DECLARE_SETTINGGROUP(AirMap)
{
INIT_SETTINGFACT(apiKey);
INIT_SETTINGFACT(clientID);
INIT_SETTINGFACT(userName);
INIT_SETTINGFACT(password);
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<AirMapSettings>("QGroundControl.SettingsManager", 1, 0, "AirMapSettings", "Reference only");
}
DECLARE_SETTINGSFACT(AirMapSettings, apiKey)
DECLARE_SETTINGSFACT(AirMapSettings, clientID)
DECLARE_SETTINGSFACT(AirMapSettings, userName)
DECLARE_SETTINGSFACT(AirMapSettings, password)
/****************************************************************************
*
* (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 "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)
};
......@@ -17,6 +17,34 @@
#include <QVariantList>
#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
......
......@@ -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);
}
......@@ -22,6 +22,7 @@
#include "RTKSettings.h"
#include "GuidedSettings.h"
#include "BrandImageSettings.h"
#include "AirMapSettings.h"
#include <QVariantList>
......@@ -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;
......
......@@ -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);
}
......@@ -11,6 +11,7 @@
#include <QObject>
#include <QGeoCoordinate>
#include <QElapsedTimer>
#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;
};
......@@ -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;
}
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
......
......@@ -20,6 +20,7 @@
#include "MAVLinkProtocol.h"
#include "UASMessageHandler.h"
#include "SettingsFact.h"
#include <AirspaceManagement.h>
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<uint32_t, ADSBVehicle*> _adsbICAOMap;
QMap<QString, ADSBVehicle*> _trafficVehicleMap;
QTimer _adsbTimer;
// Toolbox references
FirmwarePluginManager* _firmwarePluginManager;
......
......@@ -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 {
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment