Commit c92f9ca0 authored by DonLakeFlyer's avatar DonLakeFlyer Committed by Beat Küng

add AirMap Controller & Manager

parent d9c5a95d
......@@ -500,6 +500,8 @@ HEADERS += \
src/LogCompressor.h \
src/MG.h \
src/MissionManager/CameraCalc.h \
src/MissionManager/AirMapController.h \
src/MissionManager/AirMapManager.h \
src/MissionManager/CameraSection.h \
src/MissionManager/CameraSpec.h \
src/MissionManager/ComplexMissionItem.h \
......@@ -690,6 +692,8 @@ SOURCES += \
src/JsonHelper.cc \
src/LogCompressor.cc \
src/MissionManager/CameraCalc.cc \
src/MissionManager/AirMapController.cc \
src/MissionManager/AirMapManager.cc \
src/MissionManager/CameraSection.cc \
src/MissionManager/CameraSpec.cc \
src/MissionManager/ComplexMissionItem.cc \
......
......@@ -57,7 +57,10 @@ FlightMap {
// Track last known map position and zoom from Fly view in settings
onZoomLevelChanged: QGroundControl.flightMapZoom = zoomLevel
onCenterChanged: QGroundControl.flightMapPosition = center
onCenterChanged: {
airMapController.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 +326,33 @@ FlightMap {
}
]
}
// AirMap overlap support
AirMapController {
id: airMapController
}
MapItemView {
model: airMapController.circles
delegate: MapCircle {
center: object.center
radius: object.radius
border.color: "white"
color: "yellow"
opacity: 0.25
}
}
MapItemView {
model: airMapController.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,36 @@ void JsonHelper::saveGeoCoordinate(const QGeoCoordinate& coordinate,
jsonValue = QJsonValue(coordinateArray);
}
bool JsonHelper::loadGeoCoordinate(const QJsonValue& jsonValue,
bool altitudeRequired,
QGeoCoordinate& coordinate,
QString& errorString)
{
return _loadGeoCoordinate(jsonValue, altitudeRequired, coordinate, errorString, false /* 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++) {
......
......@@ -64,23 +64,39 @@ 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
/// 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
QmlObjectListModel& list, ///< Empty list to add vertices to
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 +132,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;
......
/****************************************************************************
*
* (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 "AirMapController.h"
#include "AirMapManager.h"
#include "QGCApplication.h"
#include "QGCQGeoCoordinate.h"
QGC_LOGGING_CATEGORY(AirMapControllerLog, "AirMapControllerLog")
AirMapController::AirMapController(QObject* parent)
: QObject(parent)
, _manager(qgcApp()->toolbox()->airMapManager())
{
}
AirMapController::~AirMapController()
{
}
/****************************************************************************
*
* (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.
*
****************************************************************************/
#ifndef AirMapController_H
#define AirMapController_H
#include "AirMapManager.h"
#include "QGCMapPolygon.h"
#include "QGCLoggingCategory.h"
Q_DECLARE_LOGGING_CATEGORY(AirMapControllerLog)
class AirMapManager;
class AirMapController : public QObject
{
Q_OBJECT
public:
AirMapController(QObject* parent = NULL);
~AirMapController();
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(void) { return _manager->polygonRestrictions(); }
QmlObjectListModel* circles(void) { return _manager->circularRestrictions(); }
private:
AirMapManager* _manager;
QmlObjectListModel _polygonList;
QmlObjectListModel _circleList;
};
#endif
/****************************************************************************
*
* (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 "AirMapManager.h"
#include "Vehicle.h"
#include "QmlObjectListModel.h"
#include "JsonHelper.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include <QNetworkAccessManager>
#include <QUrlQuery>
#include <QJsonDocument>
#include <QJsonArray>
#include <QNetworkProxy>
QGC_LOGGING_CATEGORY(AirMapManagerLog, "AirMapManagerLog")
AirMapManager::AirMapManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
{
_updateTimer.setInterval(5000);
_updateTimer.setSingleShot(true);
connect(&_updateTimer, &QTimer::timeout, this, &AirMapManager::_updateToROI);
}
AirMapManager::~AirMapManager()
{
}
void AirMapManager::setROI(QGeoCoordinate& center, double radiusMeters)
{
_roiCenter = center;
_roiRadius = radiusMeters;
_updateTimer.start();
}
void AirMapManager::_get(QUrl url)
{
QNetworkRequest request(url);
qDebug() << url.toString(QUrl::FullyEncoded);
qDebug() << _toolbox->settingsManager()->appSettings()->airMapKey()->rawValueString();
request.setRawHeader("X-API-Key", _toolbox->settingsManager()->appSettings()->airMapKey()->rawValueString().toUtf8());
QNetworkProxy tProxy;
tProxy.setType(QNetworkProxy::DefaultProxy);
_networkManager.setProxy(tProxy);
QNetworkReply* networkReply = _networkManager.get(request);
if (!networkReply) {
// FIXME
qWarning() << "QNetworkAccessManager::get failed";
return;
}
connect(networkReply, &QNetworkReply::finished, this, &AirMapManager::_getFinished);
connect(networkReply, static_cast<void (QNetworkReply::*)(QNetworkReply::NetworkError)>(&QNetworkReply::error), this, &AirMapManager::_getError);
}
void AirMapManager::_getFinished(void)
{
QNetworkReply* reply = qobject_cast<QNetworkReply*>(QObject::sender());
// When an error occurs we still end up here. So bail out in those cases.
if (reply->error() != QNetworkReply::NoError) {
return;
}
// Check for redirection
QVariant redirectionTarget = reply->attribute(QNetworkRequest::RedirectionTargetAttribute);
if (!redirectionTarget.isNull()) {
QUrl redirectUrl = reply->url().resolved(redirectionTarget.toUrl());
_get(redirectUrl);
reply->deleteLater();
return;
}
qDebug() << "_getFinished";
QByteArray responseBytes = reply->readAll();
//qDebug() << responseBytes;
QJsonParseError parseError;
QJsonDocument responseJson = QJsonDocument::fromJson(responseBytes, &parseError);
// FIXME: Error handling
qDebug() << responseJson.isNull() << parseError.errorString();
//qDebug().noquote() << responseJson.toJson();
_parseAirspaceJson(responseJson);
}
void AirMapManager::_getError(QNetworkReply::NetworkError code)
{
QNetworkReply* reply = qobject_cast<QNetworkReply*>(QObject::sender());
QString errorMsg;
if (code == QNetworkReply::OperationCanceledError) {
errorMsg = "Download cancelled";
} else if (code == QNetworkReply::ContentNotFoundError) {
errorMsg = "Error: File Not Found";
} else {
errorMsg = QString("Error during download. Error: (%1, %2)").arg(code).arg(reply->errorString());
}
// FIXME
qWarning() << errorMsg;
}
void AirMapManager::_updateToROI(void)
{
// Build up the polygon for the query
QJsonObject polygonJson;
polygonJson["type"] = "Polygon";
QGeoCoordinate left = _roiCenter.atDistanceAndAzimuth(_roiRadius, -90);
QGeoCoordinate right = _roiCenter.atDistanceAndAzimuth(_roiRadius, 90);
QGeoCoordinate top = _roiCenter.atDistanceAndAzimuth(_roiRadius, 0);
QGeoCoordinate bottom = _roiCenter.atDistanceAndAzimuth(_roiRadius, 180);
QGeoCoordinate topLeft(top.latitude(), left.longitude());
QGeoCoordinate topRight(top.latitude(), right.longitude());
QGeoCoordinate bottomLeft(bottom.latitude(), left.longitude());
QGeoCoordinate bottomRight(bottom.latitude(), left.longitude());
QJsonValue coordValue;
QJsonArray rgVertex;
// GeoJson polygons are right handed and include duplicate first and last vertex
JsonHelper::saveGeoJsonCoordinate(topLeft, false /* writeAltitude */, coordValue);
rgVertex.append(coordValue);
JsonHelper::saveGeoJsonCoordinate(bottomLeft, false /* writeAltitude */, coordValue);
rgVertex.append(coordValue);
JsonHelper::saveGeoJsonCoordinate(bottomRight, false /* writeAltitude */, coordValue);
rgVertex.append(coordValue);
JsonHelper::saveGeoJsonCoordinate(topRight, false /* writeAltitude */, coordValue);
rgVertex.append(coordValue);
JsonHelper::saveGeoJsonCoordinate(topLeft, false /* writeAltitude */, coordValue);
rgVertex.append(coordValue);
QJsonArray rgPolygon;
rgPolygon.append(rgVertex);
polygonJson["coordinates"] = rgPolygon;
QJsonDocument polygonJsonDoc(polygonJson);
// Build up the http query
QUrlQuery airspaceQuery;
airspaceQuery.addQueryItem(QStringLiteral("geometry"), QString::fromUtf8(polygonJsonDoc.toJson(QJsonDocument::Compact)));
airspaceQuery.addQueryItem(QStringLiteral("types"), QStringLiteral("airport,controlled_airspace,tfr,wildfire"));
airspaceQuery.addQueryItem(QStringLiteral("full"), QStringLiteral("true"));
airspaceQuery.addQueryItem(QStringLiteral("geometry_format"), QStringLiteral("geojson"));
QUrl airMapAirspaceUrl(QStringLiteral("https://api.airmap.com/airspace/v2/search"));
airMapAirspaceUrl.setQuery(airspaceQuery);
_get(airMapAirspaceUrl);
}
void AirMapManager::_parseAirspaceJson(const QJsonDocument& airspaceDoc)
{
if (!airspaceDoc.isObject()) {
// FIXME
return;
}
_polygonList.clearAndDeleteContents();
_circleList.clearAndDeleteContents();
QJsonObject rootObject = airspaceDoc.object();
const QJsonArray& airspaceArray = rootObject["data"].toArray();
for (int i=0; i< airspaceArray.count(); i++) {
const QJsonObject& airspaceObject = airspaceArray[i].toObject();
QString airspaceType(airspaceObject["type"].toString());
qDebug() << airspaceType;
qDebug() << airspaceObject["name"].toString();
QGeoCoordinate center(airspaceObject["latitude"].toDouble(), airspaceObject["longitude"].toDouble());
qDebug() << center;
if (airspaceType == "airport") {
_circleList.append(new CircularAirspaceRestriction(center, 8046.72));
}
}
}
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)
{
}
/****************************************************************************
*
* (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.
*
****************************************************************************/
#ifndef AirMapManager_H
#define AirMapManager_H
#include "QGCToolbox.h"
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
#include <QGeoCoordinate>
#include <QList>
#include <QNetworkAccessManager>
#include <QNetworkReply>
#include <QTimer>
Q_DECLARE_LOGGING_CATEGORY(AirMapManagerLog)
/// AirMap server communication support.
class AirMapManager : public QGCTool
{
Q_OBJECT
public:
AirMapManager(QGCApplication* app, QGCToolbox* toolbox);
~AirMapManager();
/// Set the ROI for airspace information
/// @param center Center coordinate for ROI
/// @param radiusMeters Radius in meters around center which is of interest
void setROI(QGeoCoordinate& center, double radiusMeters);
QmlObjectListModel* polygonRestrictions(void) { return &_polygonList; }
QmlObjectListModel* circularRestrictions(void) { return &_circleList; }
private slots:
void _getFinished(void);
void _getError(QNetworkReply::NetworkError code);
void _updateToROI(void);
private:
void _get(QUrl url);
void _parseAirspaceJson(const QJsonDocument& airspaceDoc);
QGeoCoordinate _roiCenter;
double _roiRadius;
QNetworkAccessManager _networkManager;
QTimer _updateTimer;
QmlObjectListModel _polygonList;
QmlObjectListModel _circleList;
};
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)
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;
};
#endif
......@@ -83,6 +83,7 @@
#include "QGCCameraManager.h"
#include "CameraCalc.h"
#include "VisualMissionItem.h"
#include "AirMapController.h"
#ifndef NO_SERIAL_LINK
#include "SerialLink.h"
......@@ -379,6 +380,7 @@ void QGCApplication::_initCommon(void)
qmlRegisterType<JoystickConfigController> ("QGroundControl.Controllers", 1, 0, "JoystickConfigController");
qmlRegisterType<LogDownloadController> ("QGroundControl.Controllers", 1, 0, "LogDownloadController");
qmlRegisterType<SyslinkComponentController> ("QGroundControl.Controllers", 1, 0, "SyslinkComponentController");
qmlRegisterType<AirMapController> ("QGroundControl.Controllers", 1, 0, "AirMapController");
#ifndef __mobile__
qmlRegisterType<ViewWidgetController> ("QGroundControl.Controllers", 1, 0, "ViewWidgetController");
qmlRegisterType<CustomCommandWidgetController> ("QGroundControl.Controllers", 1, 0, "CustomCommandWidgetController");
......
......@@ -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)
, _airMapManager (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);
_airMapManager = 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);
_airMapManager->setToolbox(this);
}
void QGCToolbox::_scanAndLoadPlugins(QGCApplication* app)
......
......@@ -32,6 +32,7 @@ class VideoManager;
class MAVLinkLogManager;
class QGCCorePlugin;
class SettingsManager;
class AirMapManager;
/// 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; }
AirMapManager* airMapManager(void) { return _airMapManager; }
#ifndef __mobile__
GPSManager* gpsManager(void) { return _gpsManager; }
......@@ -86,6 +88,7 @@ private:
MAVLinkLogManager* _mavlinkLogManager;
QGCCorePlugin* _corePlugin;
SettingsManager* _settingsManager;
AirMapManager* _airMapManager;
friend class QGCApplication;
};
......
......@@ -176,5 +176,10 @@
"shortDescription": "Default firmware type for flashing",
"type": "uint32",
"defaultValue": 12
},
{
"name": "AirMapKey",
"type": "string",
"defaultValue": ""
}
]
......@@ -36,6 +36,7 @@ const char* AppSettings::autoLoadMissionsName = "AutoLoa
const char* AppSettings::mapboxTokenName = "MapboxToken";
const char* AppSettings::esriTokenName = "EsriToken";
const char* AppSettings::defaultFirmwareTypeName = "DefaultFirmwareType";
const char* AppSettings::airMapKeyName = "AirMapKey";
const char* AppSettings::parameterFileExtension = "params";
const char* AppSettings::planFileExtension = "plan";
......@@ -75,6 +76,7 @@ AppSettings::AppSettings(QObject* parent)
, _mapboxTokenFact(NULL)
, _esriTokenFact(NULL)
, _defaultFirmwareTypeFact(NULL)
, _airMapKeyFact(NULL)
{
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<AppSettings>("QGroundControl.SettingsManager", 1, 0, "AppSettings", "Reference only");
......@@ -389,3 +391,12 @@ Fact* AppSettings::defaultFirmwareType(void)
return _defaultFirmwareTypeFact;
}
Fact* AppSettings::airMapKey(void)
{
if (!_airMapKeyFact) {
_airMapKeyFact = _createSettingsFact(airMapKeyName);
}
return _airMapKeyFact;
}
......@@ -40,6 +40,7 @@ public:
Q_PROPERTY(Fact* mapboxToken READ mapboxToken CONSTANT)
Q_PROPERTY(Fact* esriToken READ esriToken CONSTANT)
Q_PROPERTY(Fact* defaultFirmwareType READ defaultFirmwareType CONSTANT)
Q_PROPERTY(Fact* airMapKey READ airMapKey CONSTANT)
Q_PROPERTY(QString missionSavePath READ missionSavePath NOTIFY savePathsChanged)
Q_PROPERTY(QString parameterSavePath READ parameterSavePath NOTIFY savePathsChanged)
......@@ -75,6 +76,7 @@ public:
Fact* mapboxToken (void);
Fact* esriToken (void);
Fact* defaultFirmwareType (void);
Fact* airMapKey (void);
QString missionSavePath (void);
QString parameterSavePath (void);
......@@ -107,6 +109,7 @@ public:
static const char* mapboxTokenName;
static const char* esriTokenName;
static const char* defaultFirmwareTypeName;
static const char* airMapKeyName;
// Application wide file extensions
static const char* parameterFileExtension;
......@@ -154,6 +157,7 @@ private:
SettingsFact* _mapboxTokenFact;
SettingsFact* _esriTokenFact;
SettingsFact* _defaultFirmwareTypeFact;
SettingsFact* _airMapKeyFact;
};
#endif
......@@ -388,6 +388,11 @@ QGCView {
}
}
}
// FIXME: Hack
FactTextField {
fact: QGroundControl.settingsManager.appSettings.airMapKey
}
}
}
......
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