From 3a0f835760badf4d0f2af14ff77f2943d679c251 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 30 Jul 2017 12:48:41 -0700 Subject: [PATCH] Terrain display in MissionItemStatus --- qgroundcontrol.pro | 2 + src/MissionManager/MissionController.cc | 18 +++-- src/MissionManager/MissionSettingsItem.cc | 20 ++++- src/MissionManager/MissionSettingsItem.h | 5 ++ src/MissionManager/SimpleMissionItem.h | 1 + src/MissionManager/VisualMissionItem.cc | 92 ++++++++++++++++----- src/MissionManager/VisualMissionItem.h | 19 +++++ src/PlanView/MissionItemStatus.qml | 17 +++- src/Terrain.cc | 98 +++++++++++++++++++++++ src/Terrain.h | 55 +++++++++++++ 10 files changed, 293 insertions(+), 34 deletions(-) create mode 100644 src/Terrain.cc create mode 100644 src/Terrain.h diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index dcd8c080d..10bd5e234 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -556,6 +556,7 @@ HEADERS += \ src/Settings/SettingsManager.h \ src/Settings/UnitsSettings.h \ src/Settings/VideoSettings.h \ + src/Terrain.h \ src/Vehicle/MAVLinkLogManager.h \ src/VehicleSetup/JoystickConfigController.h \ src/audio/QGCAudioWorker.h \ @@ -732,6 +733,7 @@ SOURCES += \ src/Settings/SettingsManager.cc \ src/Settings/UnitsSettings.cc \ src/Settings/VideoSettings.cc \ + src/Terrain.cc \ src/Vehicle/MAVLinkLogManager.cc \ src/VehicleSetup/JoystickConfigController.cc \ src/audio/QGCAudioWorker.cpp \ diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index d5d9c58ae..fca40a177 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -1206,13 +1206,10 @@ void MissionController::_recalcMissionFlightStatus() minAltSeen = std::min(minAltSeen, absoluteAltitude); maxAltSeen = std::max(maxAltSeen, absoluteAltitude); - if (!item->exitCoordinateSameAsEntry()) { - absoluteAltitude = item->exitCoordinate().altitude(); - if (item->exitCoordinateHasRelativeAltitude()) { - absoluteAltitude += homePositionAltitude; - } - minAltSeen = std::min(minAltSeen, absoluteAltitude); - maxAltSeen = std::max(maxAltSeen, absoluteAltitude); + double terrainAltitude = item->terrainAltitude(); + if (!qIsNaN(terrainAltitude)) { + minAltSeen = std::min(minAltSeen, terrainAltitude); + maxAltSeen = std::max(maxAltSeen, terrainAltitude); } if (!item->isStandaloneCoordinate()) { @@ -1290,8 +1287,12 @@ void MissionController::_recalcMissionFlightStatus() } if (altRange == 0.0) { item->setAltPercent(0.0); + item->setTerrainPercent(qQNaN()); } else { item->setAltPercent((absoluteAltitude - minAltSeen) / altRange); + if (!qIsNaN(item->terrainAltitude())) { + item->setTerrainPercent((item->terrainAltitude() - minAltSeen) / altRange); + } } } } @@ -1419,6 +1420,7 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem) connect(visualItem, &VisualMissionItem::exitCoordinateHasRelativeAltitudeChanged, this, &MissionController::_recalcWaypointLines); connect(visualItem, &VisualMissionItem::specifiedFlightSpeedChanged, this, &MissionController::_recalcMissionFlightStatus); connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged, this, &MissionController::_recalcMissionFlightStatus); + connect(visualItem, &VisualMissionItem::terrainAltitudeChanged, this, &MissionController::_recalcMissionFlightStatus); connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged, this, &MissionController::_recalcSequence); if (visualItem->isSimpleItem()) { @@ -1494,7 +1496,7 @@ void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& if (_visualItems) { MissionSettingsItem* settingsItem = qobject_cast(_visualItems->get(0)); if (settingsItem) { - settingsItem->setCoordinate(homePosition); + settingsItem->setHomePositionFromVehicle(homePosition); } else { qWarning() << "First item is not MissionSettingsItem"; } diff --git a/src/MissionManager/MissionSettingsItem.cc b/src/MissionManager/MissionSettingsItem.cc index a19412bd8..d3e60847e 100644 --- a/src/MissionManager/MissionSettingsItem.cc +++ b/src/MissionManager/MissionSettingsItem.cc @@ -30,6 +30,7 @@ QMap MissionSettingsItem::_metaDataMap; MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent) : ComplexMissionItem (vehicle, parent) , _plannedHomePositionAltitudeFact (0, _plannedHomePositionAltitudeName, FactMetaData::valueTypeDouble) + , _plannedHomePositionFromVehicle (false) , _missionEndRTL (false) , _cameraSection (vehicle) , _speedSection (vehicle) @@ -54,9 +55,10 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent) connect(&_cameraSection, &CameraSection::itemCountChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber); connect(&_speedSection, &CameraSection::itemCountChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber); - connect(&_plannedHomePositionAltitudeFact, &Fact::valueChanged, this, &MissionSettingsItem::_setDirty); + connect(this, &MissionSettingsItem::terrainAltitudeChanged, this, &MissionSettingsItem::_setHomeAltFromTerrain); - connect(&_plannedHomePositionAltitudeFact, &Fact::valueChanged, this, &MissionSettingsItem::_updateAltitudeInCoordinate); + connect(&_plannedHomePositionAltitudeFact, &Fact::valueChanged, this, &MissionSettingsItem::_setDirty); + connect(&_plannedHomePositionAltitudeFact, &Fact::valueChanged, this, &MissionSettingsItem::_updateAltitudeInCoordinate); connect(&_cameraSection, &CameraSection::dirtyChanged, this, &MissionSettingsItem::_sectionDirtyChanged); connect(&_speedSection, &SpeedSection::dirtyChanged, this, &MissionSettingsItem::_sectionDirtyChanged); @@ -65,7 +67,6 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent) connect(&_cameraSection, &CameraSection::specifiedGimbalYawChanged, this, &MissionSettingsItem::specifiedGimbalYawChanged); } - int MissionSettingsItem::lastSequenceNumber(void) const { int lastSequenceNumber = _sequenceNumber; @@ -221,6 +222,12 @@ void MissionSettingsItem::_setDirty(void) setDirty(true); } +void MissionSettingsItem::setHomePositionFromVehicle(const QGeoCoordinate& coordinate) +{ + _plannedHomePositionFromVehicle = true; + setCoordinate(coordinate); +} + void MissionSettingsItem::setCoordinate(const QGeoCoordinate& coordinate) { if (_plannedHomePositionCoordinate != coordinate) { @@ -281,3 +288,10 @@ void MissionSettingsItem::setMissionEndRTL(bool missionEndRTL) emit missionEndRTLChanged(missionEndRTL); } } + +void MissionSettingsItem::_setHomeAltFromTerrain(double terrainAltitude) +{ + if (!_plannedHomePositionFromVehicle) { + _plannedHomePositionAltitudeFact.setRawValue(terrainAltitude); + } +} diff --git a/src/MissionManager/MissionSettingsItem.h b/src/MissionManager/MissionSettingsItem.h index a37150cf7..c61a6d7e7 100644 --- a/src/MissionManager/MissionSettingsItem.h +++ b/src/MissionManager/MissionSettingsItem.h @@ -48,6 +48,9 @@ public: /// @return true: Mission end action was added bool addMissionEndAction(QList& items, int seqNum, QObject* missionItemParent); + /// Called to updaet home position coordinate when it comes from a connected vehicle + void setHomePositionFromVehicle(const QGeoCoordinate& coordinate); + // Overrides from ComplexMissionItem double complexDistance (void) const final; @@ -94,10 +97,12 @@ private slots: void _setDirty (void); void _sectionDirtyChanged (bool dirty); void _updateAltitudeInCoordinate (QVariant value); + void _setHomeAltFromTerrain (double terrainAltitude); private: QGeoCoordinate _plannedHomePositionCoordinate; // Does not include altitude Fact _plannedHomePositionAltitudeFact; + bool _plannedHomePositionFromVehicle; bool _missionEndRTL; CameraSection _cameraSection; SpeedSection _speedSection; diff --git a/src/MissionManager/SimpleMissionItem.h b/src/MissionManager/SimpleMissionItem.h index f57d8b606..2e0e0cafe 100644 --- a/src/MissionManager/SimpleMissionItem.h +++ b/src/MissionManager/SimpleMissionItem.h @@ -140,6 +140,7 @@ private slots: void _updateLastSequenceNumber (void); void _rebuildFacts (void); + private: void _connectSignals (void); void _setupMetaData (void); diff --git a/src/MissionManager/VisualMissionItem.cc b/src/MissionManager/VisualMissionItem.cc index 0e3c58672..a108dde19 100644 --- a/src/MissionManager/VisualMissionItem.cc +++ b/src/MissionManager/VisualMissionItem.cc @@ -15,39 +15,50 @@ #include "FirmwarePluginManager.h" #include "QGCApplication.h" #include "JsonHelper.h" +#include "Terrain.h" const char* VisualMissionItem::jsonTypeKey = "type"; const char* VisualMissionItem::jsonTypeSimpleItemValue = "SimpleItem"; const char* VisualMissionItem::jsonTypeComplexItemValue = "ComplexItem"; VisualMissionItem::VisualMissionItem(Vehicle* vehicle, QObject* parent) - : QObject(parent) - , _vehicle(vehicle) - , _isCurrentItem(false) - , _dirty(false) - , _homePositionSpecialCase(false) - , _altDifference(0.0) - , _altPercent(0.0) - , _azimuth(0.0) - , _distance(0.0) - , _missionGimbalYaw(std::numeric_limits::quiet_NaN()) - , _missionVehicleYaw(std::numeric_limits::quiet_NaN()) + : QObject (parent) + , _vehicle (vehicle) + , _isCurrentItem (false) + , _dirty (false) + , _homePositionSpecialCase (false) + , _terrainAltitude (qQNaN()) + , _altDifference (0.0) + , _altPercent (0.0) + , _terrainPercent (qQNaN()) + , _azimuth (0.0) + , _distance (0.0) + , _missionGimbalYaw (qQNaN()) + , _missionVehicleYaw (qQNaN()) + , _lastLatTerrainQuery (0) + , _lastLonTerrainQuery (0) { + _updateTerrainTimer.setInterval(500); + _updateTerrainTimer.setSingleShot(true); + connect(&_updateTerrainTimer, &QTimer::timeout, this, &VisualMissionItem::_reallyUpdateTerrainAltitude); + connect(this, &VisualMissionItem::coordinateChanged, this, &VisualMissionItem::_updateTerrainAltitude); } VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, QObject* parent) - : QObject(parent) - , _vehicle(NULL) - , _isCurrentItem(false) - , _dirty(false) - , _homePositionSpecialCase(false) - , _altDifference(0.0) - , _altPercent(0.0) - , _azimuth(0.0) - , _distance(0.0) + : QObject (parent) + , _vehicle (NULL) + , _isCurrentItem (false) + , _dirty (false) + , _homePositionSpecialCase (false) + , _altDifference (0.0) + , _altPercent (0.0) + , _terrainPercent (qQNaN()) + , _azimuth (0.0) + , _distance (0.0) { *this = other; + connect(this, &VisualMissionItem::coordinateChanged, this, &VisualMissionItem::_updateTerrainAltitude); } const VisualMissionItem& VisualMissionItem::operator=(const VisualMissionItem& other) @@ -57,8 +68,10 @@ const VisualMissionItem& VisualMissionItem::operator=(const VisualMissionItem& o setIsCurrentItem(other._isCurrentItem); setDirty(other._dirty); _homePositionSpecialCase = other._homePositionSpecialCase; + _terrainAltitude = other._terrainAltitude; setAltDifference(other._altDifference); setAltPercent(other._altPercent); + setTerrainPercent(other._terrainPercent); setAzimuth(other._azimuth); setDistance(other._distance); @@ -101,6 +114,14 @@ void VisualMissionItem::setAltPercent(double altPercent) } } +void VisualMissionItem::setTerrainPercent(double terrainPercent) +{ + if (!qFuzzyCompare(_terrainPercent, terrainPercent)) { + _terrainPercent = terrainPercent; + emit terrainPercentChanged(terrainPercent); + } +} + void VisualMissionItem::setAzimuth(double azimuth) { if (!qFuzzyCompare(_azimuth, azimuth)) { @@ -128,3 +149,34 @@ void VisualMissionItem::setMissionVehicleYaw(double vehicleYaw) emit missionVehicleYawChanged(_missionVehicleYaw); } } + +void VisualMissionItem::_updateTerrainAltitude(void) +{ + if (coordinate().isValid()) { + // We use a timer so that any additional requests before the timer fires result in only a single request + _updateTerrainTimer.start(); + } +} + +void VisualMissionItem::_reallyUpdateTerrainAltitude(void) +{ + QGeoCoordinate coord = coordinate(); + if (coord.isValid() && (qIsNaN(_terrainAltitude) || !qFuzzyCompare(_lastLatTerrainQuery, coord.latitude()) || qFuzzyCompare(_lastLonTerrainQuery, coord.longitude()))) { + _lastLatTerrainQuery = coord.latitude(); + _lastLonTerrainQuery = coord.longitude(); + ElevationProvider* terrain = new ElevationProvider(this); + connect(terrain, &ElevationProvider::terrainData, this, &VisualMissionItem::_terrainDataReceived); + QList rgCoord; + rgCoord.append(coordinate()); + terrain->queryTerrainData(rgCoord); + } +} + +void VisualMissionItem::_terrainDataReceived(bool success, QList altitudes) +{ + if (success) { + _terrainAltitude = altitudes[0]; + emit terrainAltitudeChanged(_terrainAltitude); + sender()->deleteLater(); + } +} diff --git a/src/MissionManager/VisualMissionItem.h b/src/MissionManager/VisualMissionItem.h index 56d3872b3..fbd3d34eb 100644 --- a/src/MissionManager/VisualMissionItem.h +++ b/src/MissionManager/VisualMissionItem.h @@ -45,6 +45,7 @@ public: Q_PROPERTY(bool homePosition READ homePosition CONSTANT) ///< true: This item is being used as a home position indicator Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged) ///< This is the entry point for a waypoint line into the item. For a simple item it is also the location of the item + Q_PROPERTY(double terrainAltitude READ terrainAltitude NOTIFY terrainAltitudeChanged) ///< The altitude of terrain at the coordinate position, NaN if not known Q_PROPERTY(bool coordinateHasRelativeAltitude READ coordinateHasRelativeAltitude NOTIFY coordinateHasRelativeAltitudeChanged) ///< true: coordinate.latitude is relative to home altitude Q_PROPERTY(QGeoCoordinate exitCoordinate READ exitCoordinate NOTIFY exitCoordinateChanged) ///< This is the exit point for a waypoint line coming out of the item. Q_PROPERTY(bool exitCoordinateHasRelativeAltitude READ exitCoordinateHasRelativeAltitude NOTIFY exitCoordinateHasRelativeAltitudeChanged) ///< true: coordinate.latitude is relative to home altitude @@ -72,6 +73,7 @@ public: Q_PROPERTY(double altDifference READ altDifference WRITE setAltDifference NOTIFY altDifferenceChanged) ///< Change in altitude from previous waypoint Q_PROPERTY(double altPercent READ altPercent WRITE setAltPercent NOTIFY altPercentChanged) ///< Percent of total altitude change in mission altitude + Q_PROPERTY(double terrainPercent READ terrainPercent WRITE setTerrainPercent NOTIFY terrainPercentChanged) ///< Percent of terrain altitude in mission altitude Q_PROPERTY(double azimuth READ azimuth WRITE setAzimuth NOTIFY azimuthChanged) ///< Azimuth to previous waypoint Q_PROPERTY(double distance READ distance WRITE setDistance NOTIFY distanceChanged) ///< Distance to previous waypoint @@ -82,15 +84,18 @@ public: double altDifference (void) const { return _altDifference; } double altPercent (void) const { return _altPercent; } + double terrainPercent (void) const { return _terrainPercent; } double azimuth (void) const { return _azimuth; } double distance (void) const { return _distance; } bool isCurrentItem (void) const { return _isCurrentItem; } + double terrainAltitude (void) const { return _terrainAltitude; } QmlObjectListModel* childItems(void) { return &_childItems; } void setIsCurrentItem (bool isCurrentItem); void setAltDifference (double altDifference); void setAltPercent (double altPercent); + void setTerrainPercent (double terrainPercent); void setAzimuth (double azimuth); void setDistance (double distance); @@ -151,6 +156,7 @@ public: signals: void altDifferenceChanged (double altDifference); void altPercentChanged (double altPercent); + void terrainPercentChanged (double terrainPercent); void azimuthChanged (double azimuth); void commandDescriptionChanged (void); void commandNameChanged (void); @@ -170,6 +176,7 @@ signals: void lastSequenceNumberChanged (int sequenceNumber); void missionGimbalYawChanged (double missionGimbalYaw); void missionVehicleYawChanged (double missionVehicleYaw); + void terrainAltitudeChanged (double terrainAltitude); void coordinateHasRelativeAltitudeChanged (bool coordinateHasRelativeAltitude); void exitCoordinateHasRelativeAltitudeChanged (bool exitCoordinateHasRelativeAltitude); @@ -180,8 +187,10 @@ protected: bool _isCurrentItem; bool _dirty; bool _homePositionSpecialCase; ///< true: This item is being used as a ui home position indicator + double _terrainAltitude; ///< Altitude of terrain at coordinate position, NaN for not known double _altDifference; ///< Difference in altitude from previous waypoint double _altPercent; ///< Percent of total altitude change in mission + double _terrainPercent; ///< Percent of terrain altitude for coordinate double _azimuth; ///< Azimuth to previous waypoint double _distance; ///< Distance to previous waypoint QString _editorQml; ///< Qml resource for editing item @@ -192,6 +201,16 @@ protected: /// This is used to reference any subsequent mission items which do not specify a coordinate. QmlObjectListModel _childItems; + +private slots: + void _updateTerrainAltitude (void); + void _reallyUpdateTerrainAltitude (void); + void _terrainDataReceived (bool success, QList altitudes); + +private: + QTimer _updateTerrainTimer; + double _lastLatTerrainQuery; + double _lastLonTerrainQuery; }; #endif diff --git a/src/PlanView/MissionItemStatus.qml b/src/PlanView/MissionItemStatus.qml index 193ffdb8c..a3ba149c6 100644 --- a/src/PlanView/MissionItemStatus.qml +++ b/src/PlanView/MissionItemStatus.qml @@ -35,7 +35,7 @@ Rectangle { id: label anchors.top: parent.bottom width: parent.height - text: qsTr("Altitude") + text: qsTr("Terrain Altitude") horizontalAlignment: Text.AlignHCenter rotation: -90 transformOrigin: Item.TopLeft @@ -62,10 +62,21 @@ Rectangle { visible: display property real availableHeight: height - indicator.height - property bool graphAbsolute: true + property bool showTerrain: !isNaN(object.terrainPercent) + property real _terrainPercent: showTerrain ? object.terrainPercent : 0 + readonly property bool display: object.specifiesCoordinate && !object.isStandaloneCoordinate readonly property real spacing: ScreenTools.defaultFontPixelWidth * ScreenTools.smallFontPointRatio + Rectangle { + anchors.bottom: parent.bottom + anchors.horizontalCenter: parent.horizontalCenter + width: indicator.width + height: Math.max(availableHeight * _terrainPercent, 1) + color: _terrainPercent > object.altPercent ? "red": qgcPal.text + visible: !isNaN(object.terrainPercent) + } + MissionItemIndexLabel { id: indicator anchors.horizontalCenter: parent.horizontalCenter @@ -74,7 +85,7 @@ Rectangle { checked: object.isCurrentItem label: object.abbreviation.charAt(0) index: object.sequenceNumber - visible: object.relativeAltitude ? true : (object.homePosition || graphAbsolute) + visible: object.relativeAltitude ? true : object.homePosition } } } diff --git a/src/Terrain.cc b/src/Terrain.cc new file mode 100644 index 000000000..9203481ba --- /dev/null +++ b/src/Terrain.cc @@ -0,0 +1,98 @@ +/**************************************************************************** + * + * (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 "Terrain.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +ElevationProvider::ElevationProvider(QObject* parent) + : QObject(parent) +{ + +} + +bool ElevationProvider::queryTerrainData(const QList& coordinates) +{ + if (_state != State::Idle || coordinates.length() == 0) { + return false; + } + + QUrlQuery query; + QString points = ""; + for (const auto& coordinate : coordinates) { + points += QString::number(coordinate.latitude(), 'f', 10) + "," + + QString::number(coordinate.longitude(), 'f', 10) + ","; + } + points = points.mid(0, points.length() - 1); // remove the last ',' + + query.addQueryItem(QStringLiteral("points"), points); + QUrl url(QStringLiteral("https://api.airmap.com/elevation/stage/srtm1/ele")); + url.setQuery(query); + + QNetworkRequest request(url); + + QNetworkProxy tProxy; + tProxy.setType(QNetworkProxy::DefaultProxy); + _networkManager.setProxy(tProxy); + + QNetworkReply* networkReply = _networkManager.get(request); + if (!networkReply) { + return false; + } + + connect(networkReply, &QNetworkReply::finished, this, &ElevationProvider::_requestFinished); + + _state = State::Downloading; + return true; +} + +void ElevationProvider::_requestFinished() +{ + QNetworkReply* reply = qobject_cast(QObject::sender()); + QList altitudes; + _state = State::Idle; + + // When an error occurs we still end up here + if (reply->error() != QNetworkReply::NoError) { + QByteArray responseBytes = reply->readAll(); + + QJsonParseError parseError; + QJsonDocument responseJson = QJsonDocument::fromJson(responseBytes, &parseError); + qDebug() << responseJson; + emit terrainData(false, altitudes); + return; + } + + QByteArray responseBytes = reply->readAll(); + + QJsonParseError parseError; + QJsonDocument responseJson = QJsonDocument::fromJson(responseBytes, &parseError); + if (parseError.error != QJsonParseError::NoError) { + emit terrainData(false, altitudes); + return; + } + QJsonObject rootObject = responseJson.object(); + QString status = rootObject["status"].toString(); + if (status == "success") { + const QJsonArray& dataArray = rootObject["data"].toArray(); + for (int i = 0; i < dataArray.count(); i++) { + altitudes.push_back(dataArray[i].toDouble()); + } + + emit terrainData(true, altitudes); + } + emit terrainData(false, altitudes); +} diff --git a/src/Terrain.h b/src/Terrain.h new file mode 100644 index 000000000..bfc987f74 --- /dev/null +++ b/src/Terrain.h @@ -0,0 +1,55 @@ +/**************************************************************************** + * + * (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 +#include +#include + +/* usage example: + ElevationProvider *p = new ElevationProvider(); + QList coordinates; + QGeoCoordinate c(47.379243, 8.548265); + coordinates.push_back(c); + c.setLatitude(c.latitude()+0.01); + coordinates.push_back(c); + p->queryTerrainData(coordinates); + */ + + +class ElevationProvider : public QObject +{ + Q_OBJECT +public: + ElevationProvider(QObject* parent = NULL); + + /** + * Async elevation query for a list of lon,lat coordinates. When the query is done, the terrainData() signal + * is emitted. + * @param coordinates + * @return true on success + */ + bool queryTerrainData(const QList& coordinates); + +signals: + void terrainData(bool success, QList altitudes); + +private slots: + void _requestFinished(); +private: + + enum class State { + Idle, + Downloading, + }; + + State _state = State::Idle; + QNetworkAccessManager _networkManager; +}; -- 2.22.0