Commit 65369153 authored by DonLakeFlyer's avatar DonLakeFlyer

Initial support for CorridorScan terrain follow

Only adjust existing waypoints. Does not add waypoints.
parent e8e2feb7
......@@ -36,17 +36,18 @@ public:
Q_INVOKABLE void rotateEntryPoint(void);
// Overrides from ComplexMissionItem
int lastSequenceNumber (void) const final;
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
QString mapVisualQML (void) const final { return QStringLiteral("CorridorScanMapVisual.qml"); }
int lastSequenceNumber (void) const final;
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
QString mapVisualQML (void) const final { return QStringLiteral("CorridorScanMapVisual.qml"); }
// Overrides from TransectStyleComplexItem
void save (QJsonArray& planItems) final;
bool specifiesCoordinate (void) const final;
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final;
void save (QJsonArray& planItems) final;
bool specifiesCoordinate (void) const final;
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final;
// Overrides from VisualMissionionItem
bool readyForSave (void) const;
static const char* jsonComplexItemTypeValue;
......
......@@ -34,5 +34,32 @@
"shortDescription": "Refly the pattern at a 90 degree angle",
"type": "bool",
"defaultValue": false
},
{
"name": "TerrainAdjustTolerance",
"shortDescription": "TerrainAdjustTolerance",
"type": "double",
"decimalPlaces": 2,
"min": 0,
"units": "m",
"defaultValue": 10
},
{
"name": "TerrainAdjustMaxClimbRate",
"shortDescription": "TerrainAdjustMaxClimbRate",
"type": "double",
"decimalPlaces": 2,
"min": 0,
"units": "m/s",
"defaultValue": 0
},
{
"name": "TerrainAdjustMaxDescentRate",
"shortDescription": "TerrainAdjustMaxDescentRate",
"type": "double",
"decimalPlaces": 2,
"min": 0,
"units": "m/s",
"defaultValue": 0
}
]
......@@ -26,29 +26,44 @@ const char* TransectStyleComplexItem::turnAroundDistanceMultiRotorName = "Tur
const char* TransectStyleComplexItem::cameraTriggerInTurnAroundName = "CameraTriggerInTurnAround";
const char* TransectStyleComplexItem::hoverAndCaptureName = "HoverAndCapture";
const char* TransectStyleComplexItem::refly90DegreesName = "Refly90Degrees";
const char* TransectStyleComplexItem::terrainAdjustToleranceName = "TerrainAdjustTolerance";
const char* TransectStyleComplexItem::terrainAdjustMaxClimbRateName = "TerrainAdjustMaxClimbRate";
const char* TransectStyleComplexItem::terrainAdjustMaxDescentRateName = "TerrainAdjustMaxDescentRate";
const char* TransectStyleComplexItem::_jsonTransectStyleComplexItemKey = "TransectStyleComplexItem";
const char* TransectStyleComplexItem::_jsonCameraCalcKey = "CameraCalc";
const char* TransectStyleComplexItem::_jsonTransectPointsKey = "TransectPoints";
const char* TransectStyleComplexItem::_jsonItemsKey = "Items";
const int TransectStyleComplexItem::_terrainQueryTimeoutMsecs = 500;
const double TransectStyleComplexItem::_surveyEdgeIndicator = -10;
TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, QString settingsGroup, QObject* parent)
: ComplexMissionItem (vehicle, parent)
, _settingsGroup (settingsGroup)
, _sequenceNumber (0)
, _dirty (false)
, _ignoreRecalc (false)
, _complexDistance (0)
, _cameraShots (0)
, _cameraMinTriggerInterval (0)
, _cameraCalc (vehicle)
, _loadedMissionItemsParent (NULL)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/TransectStyle.SettingsGroup.json"), this))
, _turnAroundDistanceFact (_settingsGroup, _metaDataMap[_vehicle->multiRotor() ? turnAroundDistanceMultiRotorName : turnAroundDistanceName])
, _cameraTriggerInTurnAroundFact(_settingsGroup, _metaDataMap[cameraTriggerInTurnAroundName])
, _hoverAndCaptureFact (_settingsGroup, _metaDataMap[hoverAndCaptureName])
, _refly90DegreesFact (_settingsGroup, _metaDataMap[refly90DegreesName])
: ComplexMissionItem (vehicle, parent)
, _settingsGroup (settingsGroup)
, _sequenceNumber (0)
, _dirty (false)
, _terrainPolyPathQuery (NULL)
, _ignoreRecalc (false)
, _complexDistance (0)
, _cameraShots (0)
, _cameraMinTriggerInterval (0)
, _cameraCalc (vehicle)
, _followTerrain (false)
, _loadedMissionItemsParent (NULL)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/TransectStyle.SettingsGroup.json"), this))
, _turnAroundDistanceFact (_settingsGroup, _metaDataMap[_vehicle->multiRotor() ? turnAroundDistanceMultiRotorName : turnAroundDistanceName])
, _cameraTriggerInTurnAroundFact (_settingsGroup, _metaDataMap[cameraTriggerInTurnAroundName])
, _hoverAndCaptureFact (_settingsGroup, _metaDataMap[hoverAndCaptureName])
, _refly90DegreesFact (_settingsGroup, _metaDataMap[refly90DegreesName])
, _terrainAdjustToleranceFact (_settingsGroup, _metaDataMap[terrainAdjustToleranceName])
, _terrainAdjustMaxClimbRateFact (_settingsGroup, _metaDataMap[terrainAdjustMaxClimbRateName])
, _terrainAdjustMaxDescentRateFact (_settingsGroup, _metaDataMap[terrainAdjustMaxDescentRateName])
{
_terrainQueryTimer.setInterval(_terrainQueryTimeoutMsecs);
_terrainQueryTimer.setSingleShot(true);
connect(&_terrainQueryTimer, &QTimer::timeout, this, &TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo);
connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
......@@ -303,3 +318,88 @@ void TransectStyleComplexItem::_rebuildTransects(void)
_rebuildTransectsPhase1();
_rebuildTransectsPhase2();
}
void TransectStyleComplexItem::_queryTransectsPathHeightInfo(void)
{
_transectsPathHeightInfo.clear();
if (_terrainPolyPathQuery) {
// Toss previous query
_terrainPolyPathQuery->deleteLater();
_terrainPolyPathQuery = NULL;
}
if (_transectPoints.count() > 1) {
// We don't actually send the query until this timer times out. This way we only send
// the laset request if we get a bunch in a row.
_terrainQueryTimer.start();
}
}
void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void)
{
if (_transectPoints.count() > 1) {
_terrainPolyPathQuery = new TerrainPolyPathQuery(this);
connect(_terrainPolyPathQuery, &TerrainPolyPathQuery::terrainData, this, &TransectStyleComplexItem::_polyPathTerrainData);
_terrainPolyPathQuery->requestData(_transectPoints);
}
}
void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList<TerrainPathQuery::PathHeightInfo_t>& rgPathHeightInfo)
{
if (success) {
_transectsPathHeightInfo = rgPathHeightInfo;
} else {
_transectsPathHeightInfo.clear();
}
}
bool TransectStyleComplexItem::readyForSave(void) const
{
// Make sure we have the terrain data we need
return _transectPoints.count() > 1 ? _transectsPathHeightInfo.count() : false;
}
void TransectStyleComplexItem::_adjustTransectPointsForTerrain(void)
{
if (_followTerrain && !readyForSave()) {
qCWarning(TransectStyleComplexItemLog) << "_adjustTransectPointsForTerrain called when terrain data not ready";
qgcApp()->showMessage(tr("INTERNAL ERROR: TransectStyleComplexItem::_adjustTransectPointsForTerrain called when terrain data not ready. Plan will be incorrect."));
return;
}
double altitude = _cameraCalc.distanceToSurface()->rawValue().toDouble();
for (int i=0; i<_transectPoints.count() - 1; i++) {
QGeoCoordinate transectPoint = _transectPoints[i].value<QGeoCoordinate>();
bool surveyEdgeIndicator = transectPoint.altitude() == _surveyEdgeIndicator;
if (_followTerrain) {
transectPoint.setAltitude(_transectsPathHeightInfo[i].rgHeight[0] + altitude);
} else {
transectPoint.setAltitude(altitude);
}
if (surveyEdgeIndicator) {
// Use to indicate survey edge
transectPoint.setAltitude(-transectPoint.altitude());
}
_transectPoints[i] = QVariant::fromValue(transectPoint);
}
// Take care of last point
QGeoCoordinate transectPoint = _transectPoints.last().value<QGeoCoordinate>();
if (_followTerrain){
transectPoint.setAltitude(_transectsPathHeightInfo.last().rgHeight.last() + altitude);
} else {
transectPoint.setAltitude(altitude);
}
_transectPoints[_transectPoints.count() - 1] = QVariant::fromValue(transectPoint);
}
void TransectStyleComplexItem::setFollowTerrain(bool followTerrain)
{
if (followTerrain != _followTerrain) {
_followTerrain = followTerrain;
emit followTerrainChanged(followTerrain);
}
}
......@@ -16,6 +16,7 @@
#include "QGCMapPolyline.h"
#include "QGCMapPolygon.h"
#include "CameraCalc.h"
#include "TerrainQuery.h"
Q_DECLARE_LOGGING_CATEGORY(TransectStyleComplexItemLog)
......@@ -26,34 +27,45 @@ class TransectStyleComplexItem : public ComplexMissionItem
public:
TransectStyleComplexItem(Vehicle* vehicle, QString settignsGroup, QObject* parent = NULL);
Q_PROPERTY(QGCMapPolygon* surveyAreaPolygon READ surveyAreaPolygon CONSTANT)
Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT)
Q_PROPERTY(Fact* turnAroundDistance READ turnAroundDistance CONSTANT)
Q_PROPERTY(Fact* cameraTriggerInTurnAround READ cameraTriggerInTurnAround CONSTANT)
Q_PROPERTY(Fact* hoverAndCapture READ hoverAndCapture CONSTANT)
Q_PROPERTY(Fact* refly90Degrees READ refly90Degrees CONSTANT)
Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged)
Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged)
Q_PROPERTY(double coveredArea READ coveredArea NOTIFY coveredAreaChanged)
Q_PROPERTY(double cameraMinTriggerInterval READ cameraMinTriggerInterval NOTIFY cameraMinTriggerIntervalChanged)
Q_PROPERTY(bool hoverAndCaptureAllowed READ hoverAndCaptureAllowed CONSTANT)
Q_PROPERTY(QVariantList transectPoints READ transectPoints NOTIFY transectPointsChanged)
Q_PROPERTY(QGCMapPolygon* surveyAreaPolygon READ surveyAreaPolygon CONSTANT)
Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT)
Q_PROPERTY(Fact* turnAroundDistance READ turnAroundDistance CONSTANT)
Q_PROPERTY(Fact* cameraTriggerInTurnAround READ cameraTriggerInTurnAround CONSTANT)
Q_PROPERTY(Fact* hoverAndCapture READ hoverAndCapture CONSTANT)
Q_PROPERTY(Fact* refly90Degrees READ refly90Degrees CONSTANT)
Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged)
Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged)
Q_PROPERTY(double coveredArea READ coveredArea NOTIFY coveredAreaChanged)
Q_PROPERTY(double cameraMinTriggerInterval READ cameraMinTriggerInterval NOTIFY cameraMinTriggerIntervalChanged)
Q_PROPERTY(bool hoverAndCaptureAllowed READ hoverAndCaptureAllowed CONSTANT)
Q_PROPERTY(QVariantList transectPoints READ transectPoints NOTIFY transectPointsChanged)
Q_PROPERTY(bool followTerrain READ followTerrain WRITE setFollowTerrain NOTIFY followTerrainChanged)
Q_PROPERTY(Fact* terrainAdjustTolerance READ terrainAdjustTolerance CONSTANT)
Q_PROPERTY(Fact* terrainAdjustMaxDescentRate READ terrainAdjustMaxDescentRate CONSTANT)
Q_PROPERTY(Fact* terrainAdjustMaxClimbRate READ terrainAdjustMaxClimbRate CONSTANT)
QGCMapPolygon* surveyAreaPolygon (void) { return &_surveyAreaPolygon; }
CameraCalc* cameraCalc (void) { return &_cameraCalc; }
QVariantList transectPoints (void) { return _transectPoints; }
Fact* turnAroundDistance (void) { return &_turnAroundDistanceFact; }
Fact* cameraTriggerInTurnAround (void) { return &_cameraTriggerInTurnAroundFact; }
Fact* hoverAndCapture (void) { return &_hoverAndCaptureFact; }
Fact* refly90Degrees (void) { return &_refly90DegreesFact; }
Fact* turnAroundDistance (void) { return &_turnAroundDistanceFact; }
Fact* cameraTriggerInTurnAround (void) { return &_cameraTriggerInTurnAroundFact; }
Fact* hoverAndCapture (void) { return &_hoverAndCaptureFact; }
Fact* refly90Degrees (void) { return &_refly90DegreesFact; }
Fact* terrainAdjustTolerance (void) { return &_terrainAdjustToleranceFact; }
Fact* terrainAdjustMaxDescentRate (void) { return &_terrainAdjustMaxClimbRateFact; }
Fact* terrainAdjustMaxClimbRate (void) { return &_terrainAdjustMaxDescentRateFact; }
int cameraShots (void) const { return _cameraShots; }
double timeBetweenShots (void);
double coveredArea (void) const;
double cameraMinTriggerInterval(void) const { return _cameraMinTriggerInterval; }
bool hoverAndCaptureAllowed (void) const;
bool followTerrain (void) const { return _followTerrain; }
void setFollowTerrain(bool followTerrain);
// Overrides from ComplexMissionItem
......@@ -85,6 +97,7 @@ public:
double specifiedGimbalYaw (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedGimbalPitch (void) final { return std::numeric_limits<double>::quiet_NaN(); }
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
bool readyForSave (void) const override;
bool coordinateHasRelativeAltitude (void) const final { return true /*_altitudeRelative*/; }
bool exitCoordinateHasRelativeAltitude (void) const final { return true /*_altitudeRelative*/; }
......@@ -99,6 +112,9 @@ public:
static const char* cameraTriggerInTurnAroundName;
static const char* hoverAndCaptureName;
static const char* refly90DegreesName;
static const char* terrainAdjustToleranceName;
static const char* terrainAdjustMaxClimbRateName;
static const char* terrainAdjustMaxDescentRateName;
signals:
void cameraShotsChanged (void);
......@@ -106,6 +122,7 @@ signals:
void cameraMinTriggerIntervalChanged(double cameraMinTriggerInterval);
void transectPointsChanged (void);
void coveredAreaChanged (void);
void followTerrainChanged (bool followTerrain);
protected slots:
virtual void _rebuildTransectsPhase1 (void) = 0;
......@@ -115,24 +132,31 @@ protected slots:
void _setIfDirty (bool dirty);
void _updateCoordinateAltitudes (void);
void _signalLastSequenceNumberChanged (void);
void _polyPathTerrainData (bool success, const QList<TerrainPathQuery::PathHeightInfo_t>& rgPathHeightInfo);
protected:
void _save (QJsonObject& saveObject);
bool _load (const QJsonObject& complexObject, QString& errorString);
void _setExitCoordinate (const QGeoCoordinate& coordinate);
void _setCameraShots (int cameraShots);
double _triggerDistance (void) const;
bool _hasTurnaround (void) const;
double _turnaroundDistance (void) const;
void _save (QJsonObject& saveObject);
bool _load (const QJsonObject& complexObject, QString& errorString);
void _setExitCoordinate (const QGeoCoordinate& coordinate);
void _setCameraShots (int cameraShots);
double _triggerDistance (void) const;
bool _hasTurnaround (void) const;
double _turnaroundDistance (void) const;
void _queryTransectsPathHeightInfo (void);
void _adjustTransectPointsForTerrain (void);
QString _settingsGroup;
int _sequenceNumber;
bool _dirty;
QGeoCoordinate _coordinate;
QGeoCoordinate _exitCoordinate;
QVariantList _transectPoints;
QGCMapPolygon _surveyAreaPolygon;
QVariantList _transectPoints;
QList<TerrainPathQuery::PathHeightInfo_t> _transectsPathHeightInfo;
TerrainPolyPathQuery* _terrainPolyPathQuery;
QTimer _terrainQueryTimer;
bool _ignoreRecalc;
double _complexDistance;
int _cameraShots;
......@@ -140,6 +164,7 @@ protected:
double _cameraMinTriggerInterval;
double _cruiseSpeed;
CameraCalc _cameraCalc;
bool _followTerrain;
QObject* _loadedMissionItemsParent; ///< Parent for all items in _loadedMissionItems for simpler delete
QList<MissionItem*> _loadedMissionItems; ///< Mission items loaded from plan file
......@@ -150,12 +175,20 @@ protected:
SettingsFact _cameraTriggerInTurnAroundFact;
SettingsFact _hoverAndCaptureFact;
SettingsFact _refly90DegreesFact;
SettingsFact _terrainAdjustToleranceFact;
SettingsFact _terrainAdjustMaxClimbRateFact;
SettingsFact _terrainAdjustMaxDescentRateFact;
static const char* _jsonCameraCalcKey;
static const char* _jsonTransectStyleComplexItemKey;
static const char* _jsonTransectPointsKey;
static const char* _jsonItemsKey;
static const int _terrainQueryTimeoutMsecs;
static const double _surveyEdgeIndicator; ///< Altitude value in _transectPoints which indicates survey entry
private slots:
void _rebuildTransects(void);
void _rebuildTransects (void);
void _reallyQueryTransectsPathHeightInfo (void);
};
......@@ -56,6 +56,11 @@ Rectangle {
anchors.right: parent.right
spacing: _margin
QGCLabel {
text: "WIP: Careful!"
color: qgcPal.warningText
}
QGCLabel {
anchors.left: parent.left
anchors.right: parent.right
......@@ -126,6 +131,59 @@ Rectangle {
onClicked: missionItem.rotateEntryPoint()
}
SectionHeader {
id: terrainHeader
text: qsTr("Terrain")
checked: false
}
ColumnLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: terrainHeader.checked
QGCCheckBox {
id: followsTerrainCheckBox
text: qsTr("Vehicle follows terrain")
checked: missionItem.followTerrain
onClicked: missionItem.followTerrain = checked
}
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: followsTerrainCheckBox.checked
QGCLabel {
text: "WIP: Careful!"
color: qgcPal.warningText
Layout.columnSpan: 2
}
QGCLabel { text: qsTr("Tolerance") }
FactTextField {
fact: missionItem.terrainAdjustTolerance
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Max Climb Rate") }
FactTextField {
fact: missionItem.terrainAdjustMaxClimbRate
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Max Descent Rate") }
FactTextField {
fact: missionItem.terrainAdjustMaxDescentRate
Layout.fillWidth: true
}
}
}
SectionHeader {
id: statsHeader
text: qsTr("Statistics")
......
......@@ -264,7 +264,7 @@ void TerrainAtCoordinateQuery::_signalTerrainData(bool success, QList<float>& al
TerrainPathQuery::TerrainPathQuery(QObject* parent)
: TerrainQuery(parent)
{
qRegisterMetaType<PathHeightInfo_t>();
}
void TerrainPathQuery::requestData(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord)
......@@ -287,29 +287,29 @@ void TerrainPathQuery::requestData(const QGeoCoordinate& fromCoord, const QGeoCo
void TerrainPathQuery::_getNetworkReplyFailed(void)
{
QList<double> altitudes;
emit terrainData(false, 0, 0, altitudes);
PathHeightInfo_t pathHeightInfo;
emit terrainData(false, pathHeightInfo);
}
void TerrainPathQuery::_requestFailed(QNetworkReply::NetworkError error)
{
Q_UNUSED(error);
QList<double> altitudes;
emit terrainData(false, 0, 0, altitudes);
PathHeightInfo_t pathHeightInfo;
emit terrainData(false, pathHeightInfo);
}
void TerrainPathQuery::_requestJsonParseFailed(const QString& errorString)
{
Q_UNUSED(errorString);
QList<double> altitudes;
emit terrainData(false, 0, 0, altitudes);
PathHeightInfo_t pathHeightInfo;
emit terrainData(false, pathHeightInfo);
}
void TerrainPathQuery::_requestAirmapStatusFailed(const QString& status)
{
Q_UNUSED(status);
QList<double> altitudes;
emit terrainData(false, 0, 0, altitudes);
PathHeightInfo_t pathHeightInfo;
emit terrainData(false, pathHeightInfo);
}
void TerrainPathQuery::_requestSucess(const QJsonValue& dataJsonValue)
......@@ -318,14 +318,56 @@ void TerrainPathQuery::_requestSucess(const QJsonValue& dataJsonValue)
QJsonArray stepArray = jsonObject["step"].toArray();
QJsonArray profileArray = jsonObject["profile"].toArray();
QList<double> rgProfile;
PathHeightInfo_t pathHeightInfo;
pathHeightInfo.latStep = stepArray[0].toDouble();
pathHeightInfo.lonStep = stepArray[1].toDouble();
foreach (const QJsonValue& profileValue, profileArray) {
rgProfile.append(profileValue.toDouble());
pathHeightInfo.rgHeight.append(profileValue.toDouble());
}
emit terrainData(true /* success */, pathHeightInfo);
}
TerrainPolyPathQuery::TerrainPolyPathQuery(QObject* parent)
: QObject (parent)
, _curIndex (0)
{
connect(&_pathQuery, &TerrainPathQuery::terrainData, this, &TerrainPolyPathQuery::_terrainDataReceived);
}
void TerrainPolyPathQuery::requestData(const QVariantList& polyPath)
{
QList<QGeoCoordinate> path;
foreach (const QVariant& geoVar, polyPath) {
path.append(geoVar.value<QGeoCoordinate>());
}
emit terrainData(true, // success
stepArray[0].toDouble(), // lat step
stepArray[1].toDouble(), // lon step
rgProfile);
requestData(path);
}
void TerrainPolyPathQuery::requestData(const QList<QGeoCoordinate>& polyPath)
{
// Kick off first request
_rgCoords = polyPath;
_curIndex = 0;
_pathQuery.requestData(_rgCoords[0], _rgCoords[1]);
}
void TerrainPolyPathQuery::_terrainDataReceived(bool success, const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo)
{
if (!success) {
_rgPathHeightInfo.clear();
emit terrainData(false /* success */, _rgPathHeightInfo);
return;
}
_rgPathHeightInfo.append(pathHeightInfo);
if (++_curIndex >= _rgCoords.count() - 1) {
// We've finished all requests
emit terrainData(true /* success */, _rgPathHeightInfo);
} else {
_pathQuery.requestData(_rgCoords[_curIndex], _rgCoords[_curIndex+1]);
}
}
......@@ -126,17 +126,50 @@ public:
/// @param coordinates to query
void requestData(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord);
typedef struct {
double latStep; ///< Amount of latitudinal distance between each returned height
double lonStep; ///< Amount of longitudinal distance between each returned height
QList<double> rgHeight; ///< Terrain heights along path
} PathHeightInfo_t;
signals:
/// Signalled when terrain data comes back from server
void terrainData(bool success, const PathHeightInfo_t& pathHeightInfo);
protected:
void _getNetworkReplyFailed (void) final;
void _requestFailed (QNetworkReply::NetworkError error) final;
void _requestJsonParseFailed (const QString& errorString) final;
void _requestAirmapStatusFailed (const QString& status) final;
void _requestSucess (const QJsonValue& dataJsonValue) final;
};
Q_DECLARE_METATYPE(TerrainPathQuery::PathHeightInfo_t)
class TerrainPolyPathQuery : public QObject
{
Q_OBJECT
public:
TerrainPolyPathQuery(QObject* parent = NULL);
/// Async terrain query for terrain heights for the paths between each specified QGeoCoordinate.
/// When the query is done, the terrainData() signal is emitted.
/// @param polyPath List of QGeoCoordinate
void requestData(const QVariantList& polyPath);
void requestData(const QList<QGeoCoordinate>& polyPath);
signals:
/// Signalled when terrain data comes back from server
/// @param latStep Amount of latitudinal distance between each returned height
/// @param lonStep Amount of longitudinal distance between each returned height
/// @param altitudes Altitudes along specified path
void terrainData(bool success, double latStep, double lonStep, QList<double> altitudes);
void terrainData(bool success, const QList<TerrainPathQuery::PathHeightInfo_t>& rgPathHeightInfo);
private slots:
void _terrainDataReceived(bool success, const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo);
private:
int _curIndex;
QList<QGeoCoordinate> _rgCoords;
QList<TerrainPathQuery::PathHeightInfo_t> _rgPathHeightInfo;
TerrainPathQuery _pathQuery;
};
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