Commit f3ca1c29 authored by DonLakeFlyer's avatar DonLakeFlyer

Add support for max rates and tolerance

parent 4c03e810
...@@ -36,7 +36,6 @@ public: ...@@ -36,7 +36,6 @@ public:
Q_INVOKABLE void rotateEntryPoint(void); Q_INVOKABLE void rotateEntryPoint(void);
// Overrides from ComplexMissionItem // Overrides from ComplexMissionItem
int lastSequenceNumber (void) const final;
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final; bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
QString mapVisualQML (void) const final { return QStringLiteral("CorridorScanMapVisual.qml"); } QString mapVisualQML (void) const final { return QStringLiteral("CorridorScanMapVisual.qml"); }
...@@ -56,8 +55,7 @@ public: ...@@ -56,8 +55,7 @@ public:
private slots: private slots:
void _polylineDirtyChanged (bool dirty); void _polylineDirtyChanged (bool dirty);
void _polylineCountChanged (int count); void _rebuildCorridorPolygon (void);
void _rebuildCorridor (void);
// Overrides from TransectStyleComplexItem // Overrides from TransectStyleComplexItem
void _rebuildTransectsPhase1 (void) final; void _rebuildTransectsPhase1 (void) final;
...@@ -65,7 +63,6 @@ private slots: ...@@ -65,7 +63,6 @@ private slots:
private: private:
int _transectCount (void) const; int _transectCount (void) const;
void _rebuildCorridorPolygon (void);
void _buildAndAppendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent); void _buildAndAppendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent);
void _appendLoadedMissionItems (QList<MissionItem*>& items, QObject* missionItemParent); void _appendLoadedMissionItems (QList<MissionItem*>& items, QObject* missionItemParent);
......
...@@ -24,7 +24,12 @@ void CorridorScanComplexItemTest::init(void) ...@@ -24,7 +24,12 @@ void CorridorScanComplexItemTest::init(void)
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this); _offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
_corridorItem = new CorridorScanComplexItem(_offlineVehicle, this); _corridorItem = new CorridorScanComplexItem(_offlineVehicle, this);
// _corridorItem->setTurnaroundDist(0); // Unit test written for no turnaround distance
// vehicleSpeed need for terrain calcs
MissionController::MissionFlightStatus_t missionFlightStatus;
missionFlightStatus.vehicleSpeed = 5;
_corridorItem->setMissionFlightStatus(missionFlightStatus);
_setPolyline(); _setPolyline();
_corridorItem->setDirty(false); _corridorItem->setDirty(false);
...@@ -130,10 +135,27 @@ void CorridorScanComplexItemTest::_testEntryLocation(void) ...@@ -130,10 +135,27 @@ void CorridorScanComplexItemTest::_testEntryLocation(void)
} }
#endif #endif
void CorridorScanComplexItemTest::_waitForReadyForSave(void)
{
int loops = 0;
while (loops++ < 8) {
if (_corridorItem->readyForSave()) {
return;
}
QTest::qWait(500);
}
QVERIFY(false);
}
void CorridorScanComplexItemTest::_testItemCount(void) void CorridorScanComplexItemTest::_testItemCount(void)
{ {
QList<MissionItem*> items; QList<MissionItem*> items;
_corridorItem->turnAroundDistance()->setRawValue(0);
_corridorItem->cameraTriggerInTurnAround()->setRawValue(true);
_corridorItem->appendMissionItems(items, this);
QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
items.clear();
_corridorItem->turnAroundDistance()->setRawValue(0); _corridorItem->turnAroundDistance()->setRawValue(0);
_corridorItem->cameraTriggerInTurnAround()->setRawValue(false); _corridorItem->cameraTriggerInTurnAround()->setRawValue(false);
...@@ -141,7 +163,7 @@ void CorridorScanComplexItemTest::_testItemCount(void) ...@@ -141,7 +163,7 @@ void CorridorScanComplexItemTest::_testItemCount(void)
QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber()); QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
items.clear(); items.clear();
_corridorItem->turnAroundDistance()->setRawValue(0); _corridorItem->turnAroundDistance()->setRawValue(20);
_corridorItem->cameraTriggerInTurnAround()->setRawValue(true); _corridorItem->cameraTriggerInTurnAround()->setRawValue(true);
_corridorItem->appendMissionItems(items, this); _corridorItem->appendMissionItems(items, this);
QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber()); QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
...@@ -153,8 +175,32 @@ void CorridorScanComplexItemTest::_testItemCount(void) ...@@ -153,8 +175,32 @@ void CorridorScanComplexItemTest::_testItemCount(void)
QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber()); QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
items.clear(); items.clear();
_corridorItem->setFollowTerrain(true);
_corridorItem->turnAroundDistance()->setRawValue(0);
_corridorItem->cameraTriggerInTurnAround()->setRawValue(true);
_waitForReadyForSave();
_corridorItem->appendMissionItems(items, this);
QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
items.clear();
_corridorItem->turnAroundDistance()->setRawValue(0);
_corridorItem->cameraTriggerInTurnAround()->setRawValue(false);
_waitForReadyForSave();
_corridorItem->appendMissionItems(items, this);
QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
items.clear();
_corridorItem->turnAroundDistance()->setRawValue(20); _corridorItem->turnAroundDistance()->setRawValue(20);
_corridorItem->cameraTriggerInTurnAround()->setRawValue(true); _corridorItem->cameraTriggerInTurnAround()->setRawValue(true);
_waitForReadyForSave();
_corridorItem->appendMissionItems(items, this);
QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
items.clear();
_corridorItem->turnAroundDistance()->setRawValue(20);
_corridorItem->cameraTriggerInTurnAround()->setRawValue(false);
_waitForReadyForSave();
_corridorItem->appendMissionItems(items, this); _corridorItem->appendMissionItems(items, this);
QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber()); QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
items.clear(); items.clear();
......
...@@ -36,6 +36,7 @@ private slots: ...@@ -36,6 +36,7 @@ private slots:
private: private:
void _setPolyline(void); void _setPolyline(void);
void _waitForReadyForSave(void);
enum { enum {
corridorPolygonPathChangedIndex = 0, corridorPolygonPathChangedIndex = 0,
......
...@@ -2006,3 +2006,11 @@ void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force) ...@@ -2006,3 +2006,11 @@ void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force)
emit currentPlanViewItemChanged(); emit currentPlanViewItemChanged();
} }
} }
MissionController::MissionFlightStatus_t::_MissionFlightStatus_t(void)
: cruiseSpeed (qQNaN())
, hoverSpeed (qQNaN())
, vehicleSpeed (qQNaN())
{
}
...@@ -41,7 +41,7 @@ public: ...@@ -41,7 +41,7 @@ public:
MissionController(PlanMasterController* masterController, QObject* parent = NULL); MissionController(PlanMasterController* masterController, QObject* parent = NULL);
~MissionController(); ~MissionController();
typedef struct { typedef struct _MissionFlightStatus_t {
double maxTelemetryDistance; double maxTelemetryDistance;
double totalDistance; double totalDistance;
double totalTime; double totalTime;
...@@ -63,6 +63,8 @@ public: ...@@ -63,6 +63,8 @@ public:
double cruiseAmpsTotal; ///< Total cruise amps used double cruiseAmpsTotal; ///< Total cruise amps used
int batteryChangePoint; ///< -1 for not supported, 0 for not needed int batteryChangePoint; ///< -1 for not supported, 0 for not needed
int batteriesRequired; ///< -1 for not supported int batteriesRequired; ///< -1 for not supported
_MissionFlightStatus_t(void);
} MissionFlightStatus_t; } MissionFlightStatus_t;
Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged) Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged)
......
...@@ -125,6 +125,9 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool editMode, const Miss ...@@ -125,6 +125,9 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool editMode, const Miss
if (editMode) { if (editMode) {
_rebuildFacts(); _rebuildFacts();
} }
// Signal coordinate changed to kick off terrain query
emit coordinateChanged(coordinate());
} }
SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* parent) SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* parent)
......
...@@ -39,7 +39,7 @@ public: ...@@ -39,7 +39,7 @@ public:
Q_PROPERTY(double coveredArea READ coveredArea NOTIFY coveredAreaChanged) Q_PROPERTY(double coveredArea READ coveredArea NOTIFY coveredAreaChanged)
Q_PROPERTY(double cameraMinTriggerInterval READ cameraMinTriggerInterval NOTIFY cameraMinTriggerIntervalChanged) Q_PROPERTY(double cameraMinTriggerInterval READ cameraMinTriggerInterval NOTIFY cameraMinTriggerIntervalChanged)
Q_PROPERTY(bool hoverAndCaptureAllowed READ hoverAndCaptureAllowed CONSTANT) Q_PROPERTY(bool hoverAndCaptureAllowed READ hoverAndCaptureAllowed CONSTANT)
Q_PROPERTY(QVariantList transectPoints READ transectPoints NOTIFY transectPointsChanged) Q_PROPERTY(QVariantList visualTransectPoints READ visualTransectPoints NOTIFY visualTransectPointsChanged)
Q_PROPERTY(bool followTerrain READ followTerrain WRITE setFollowTerrain NOTIFY followTerrainChanged) Q_PROPERTY(bool followTerrain READ followTerrain WRITE setFollowTerrain NOTIFY followTerrainChanged)
Q_PROPERTY(Fact* terrainAdjustTolerance READ terrainAdjustTolerance CONSTANT) Q_PROPERTY(Fact* terrainAdjustTolerance READ terrainAdjustTolerance CONSTANT)
...@@ -48,7 +48,7 @@ public: ...@@ -48,7 +48,7 @@ public:
QGCMapPolygon* surveyAreaPolygon (void) { return &_surveyAreaPolygon; } QGCMapPolygon* surveyAreaPolygon (void) { return &_surveyAreaPolygon; }
CameraCalc* cameraCalc (void) { return &_cameraCalc; } CameraCalc* cameraCalc (void) { return &_cameraCalc; }
QVariantList transectPoints (void) { return _transectPoints; } QVariantList visualTransectPoints(void) { return _visualTransectPoints; }
Fact* turnAroundDistance (void) { return &_turnAroundDistanceFact; } Fact* turnAroundDistance (void) { return &_turnAroundDistanceFact; }
Fact* cameraTriggerInTurnAround (void) { return &_cameraTriggerInTurnAroundFact; } Fact* cameraTriggerInTurnAround (void) { return &_cameraTriggerInTurnAroundFact; }
...@@ -69,7 +69,7 @@ public: ...@@ -69,7 +69,7 @@ public:
// Overrides from ComplexMissionItem // Overrides from ComplexMissionItem
int lastSequenceNumber (void) const override = 0; int lastSequenceNumber (void) const final;
QString mapVisualQML (void) const override = 0; QString mapVisualQML (void) const override = 0;
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) override = 0; bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) override = 0;
...@@ -120,19 +120,19 @@ signals: ...@@ -120,19 +120,19 @@ signals:
void cameraShotsChanged (void); void cameraShotsChanged (void);
void timeBetweenShotsChanged (void); void timeBetweenShotsChanged (void);
void cameraMinTriggerIntervalChanged(double cameraMinTriggerInterval); void cameraMinTriggerIntervalChanged(double cameraMinTriggerInterval);
void transectPointsChanged (void); void visualTransectPointsChanged (void);
void coveredAreaChanged (void); void coveredAreaChanged (void);
void followTerrainChanged (bool followTerrain); void followTerrainChanged (bool followTerrain);
protected slots: protected slots:
virtual void _rebuildTransectsPhase1 (void) = 0; virtual void _rebuildTransectsPhase1 (void) = 0; ///< Rebuilds the _transects array
virtual void _rebuildTransectsPhase2 (void) = 0; virtual void _rebuildTransectsPhase2 (void) = 0; ///< Adjust values associated with _transects array
void _setDirty (void); void _setDirty (void);
void _setIfDirty (bool dirty); void _setIfDirty (bool dirty);
void _updateCoordinateAltitudes (void); void _updateCoordinateAltitudes (void);
void _signalLastSequenceNumberChanged (void);
void _polyPathTerrainData (bool success, const QList<TerrainPathQuery::PathHeightInfo_t>& rgPathHeightInfo); void _polyPathTerrainData (bool success, const QList<TerrainPathQuery::PathHeightInfo_t>& rgPathHeightInfo);
void _rebuildTransects (void);
protected: protected:
void _save (QJsonObject& saveObject); void _save (QJsonObject& saveObject);
...@@ -142,8 +142,6 @@ protected: ...@@ -142,8 +142,6 @@ protected:
double _triggerDistance (void) const; double _triggerDistance (void) const;
bool _hasTurnaround (void) const; bool _hasTurnaround (void) const;
double _turnaroundDistance (void) const; double _turnaroundDistance (void) const;
void _queryTransectsPathHeightInfo (void);
void _adjustTransectPointsForTerrain (void);
QString _settingsGroup; QString _settingsGroup;
int _sequenceNumber; int _sequenceNumber;
...@@ -152,10 +150,23 @@ protected: ...@@ -152,10 +150,23 @@ protected:
QGeoCoordinate _exitCoordinate; QGeoCoordinate _exitCoordinate;
QGCMapPolygon _surveyAreaPolygon; QGCMapPolygon _surveyAreaPolygon;
QVariantList _transectPoints; enum CoordType {
QList<TerrainPathQuery::PathHeightInfo_t> _transectsPathHeightInfo; CoordTypeInterior,
TerrainPolyPathQuery* _terrainPolyPathQuery; CoordTypeInteriorTerrainAdded,
QTimer _terrainQueryTimer; CoordTypeSurveyEdge,
CoordTypeTurnaround
};
typedef struct {
QGeoCoordinate coord;
CoordType coordType;
} CoordInfo_t;
QVariantList _visualTransectPoints;
QList<QList<CoordInfo_t>> _transects;
QList<QList<TerrainPathQuery::PathHeightInfo_t>> _transectsPathHeightInfo;
TerrainPolyPathQuery* _terrainPolyPathQuery;
QTimer _terrainQueryTimer;
bool _ignoreRecalc; bool _ignoreRecalc;
double _complexDistance; double _complexDistance;
...@@ -186,14 +197,16 @@ protected: ...@@ -186,14 +197,16 @@ protected:
static const char* _jsonFollowTerrainKey; static const char* _jsonFollowTerrainKey;
static const int _terrainQueryTimeoutMsecs; static const int _terrainQueryTimeoutMsecs;
static const double _surveyEdgeIndicator; ///< Altitude value in _transectPoints which indicates survey entry
private slots: private slots:
void _rebuildTransects (void); void _reallyQueryTransectsPathHeightInfo(void);
void _reallyQueryTransectsPathHeightInfo (void);
private: private:
void _addInterstitialTransectsForTerrain (void); void _queryTransectsPathHeightInfo (void);
double _altitudeBetweenCoords (const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord, double percentTowardsTo); void _adjustTransectsForTerrain (void);
int _maxPathHeight (const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo, int fromIndex, int toIndex, double& maxHeight); void _addInterstitialTerrainPoints (QList<CoordInfo_t>& transect, const QList<TerrainPathQuery::PathHeightInfo_t>& transectPathHeightInfo);
void _adjustForMaxRates (QList<CoordInfo_t>& transect);
void _adjustForTolerance (QList<CoordInfo_t>& transect);
double _altitudeBetweenCoords (const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord, double percentTowardsTo);
int _maxPathHeight (const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo, int fromIndex, int toIndex, double& maxHeight);
}; };
...@@ -87,7 +87,6 @@ public: ...@@ -87,7 +87,6 @@ public:
TransectStyleItem(Vehicle* vehicle, QObject* parent = NULL); TransectStyleItem(Vehicle* vehicle, QObject* parent = NULL);
// Overrides from ComplexMissionItem // Overrides from ComplexMissionItem
int lastSequenceNumber (void) const final { return _sequenceNumber; }
QString mapVisualQML (void) const final { return QString(); } QString mapVisualQML (void) const final { return QString(); }
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final { Q_UNUSED(complexObject); Q_UNUSED(sequenceNumber); Q_UNUSED(errorString); return false; } bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final { Q_UNUSED(complexObject); Q_UNUSED(sequenceNumber); Q_UNUSED(errorString); return false; }
......
...@@ -38,15 +38,7 @@ VisualMissionItem::VisualMissionItem(Vehicle* vehicle, QObject* parent) ...@@ -38,15 +38,7 @@ VisualMissionItem::VisualMissionItem(Vehicle* vehicle, QObject* parent)
, _lastLatTerrainQuery (0) , _lastLatTerrainQuery (0)
, _lastLonTerrainQuery (0) , _lastLonTerrainQuery (0)
{ {
_commonInit();
// Don't get terrain altitude information for submarines or boards
if (_vehicle->vehicleType() != MAV_TYPE_SUBMARINE && _vehicle->vehicleType() != MAV_TYPE_SURFACE_BOAT) {
_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) VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, QObject* parent)
...@@ -63,8 +55,17 @@ VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, QObject* pa ...@@ -63,8 +55,17 @@ VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, QObject* pa
{ {
*this = other; *this = other;
_commonInit();
}
void VisualMissionItem::_commonInit(void)
{
// Don't get terrain altitude information for submarines or boats // Don't get terrain altitude information for submarines or boats
if (_vehicle->vehicleType() != MAV_TYPE_SUBMARINE && _vehicle->vehicleType() != MAV_TYPE_SURFACE_BOAT) { if (_vehicle->vehicleType() != MAV_TYPE_SUBMARINE && _vehicle->vehicleType() != MAV_TYPE_SURFACE_BOAT) {
_updateTerrainTimer.setInterval(500);
_updateTerrainTimer.setSingleShot(true);
connect(&_updateTerrainTimer, &QTimer::timeout, this, &VisualMissionItem::_reallyUpdateTerrainAltitude);
connect(this, &VisualMissionItem::coordinateChanged, this, &VisualMissionItem::_updateTerrainAltitude); connect(this, &VisualMissionItem::coordinateChanged, this, &VisualMissionItem::_updateTerrainAltitude);
} }
} }
......
...@@ -214,6 +214,8 @@ private slots: ...@@ -214,6 +214,8 @@ private slots:
void _terrainDataReceived (bool success, QList<double> heights); void _terrainDataReceived (bool success, QList<double> heights);
private: private:
void _commonInit(void);
QTimer _updateTerrainTimer; QTimer _updateTerrainTimer;
double _lastLatTerrainQuery; double _lastLatTerrainQuery;
double _lastLonTerrainQuery; double _lastLonTerrainQuery;
......
...@@ -119,7 +119,7 @@ Item { ...@@ -119,7 +119,7 @@ Item {
MapPolyline { MapPolyline {
line.color: "white" line.color: "white"
line.width: 2 line.width: 2
path: _missionItem.transectPoints path: _missionItem.visualTransectPoints
} }
} }
} }
...@@ -80,8 +80,8 @@ void TerrainAirMapQuery::requestCarpetHeights(const QGeoCoordinate& swCoord, con ...@@ -80,8 +80,8 @@ void TerrainAirMapQuery::requestCarpetHeights(const QGeoCoordinate& swCoord, con
void TerrainAirMapQuery::_sendQuery(const QString& path, const QUrlQuery& urlQuery) void TerrainAirMapQuery::_sendQuery(const QString& path, const QUrlQuery& urlQuery)
{ {
QUrl url(QStringLiteral("https://api.airmap.com/elevation/v1/ele") + path); QUrl url(QStringLiteral("https://api.airmap.com/elevation/v1/ele") + path);
url.setQuery(urlQuery);
qCDebug(TerrainQueryLog) << "_sendQuery" << url; qCDebug(TerrainQueryLog) << "_sendQuery" << url;
url.setQuery(urlQuery);
QNetworkRequest request(url); QNetworkRequest request(url);
...@@ -133,7 +133,7 @@ void TerrainAirMapQuery::_requestFinished(void) ...@@ -133,7 +133,7 @@ void TerrainAirMapQuery::_requestFinished(void)
// Send back data // Send back data
const QJsonValue& jsonData = rootObject["data"]; const QJsonValue& jsonData = rootObject["data"];
qCDebug(TerrainQueryLog) << "_requestFinished" << jsonData; qCDebug(TerrainQueryLog) << "_requestFinished sucess";
switch (_queryMode) { switch (_queryMode) {
case QueryModeCoordinates: case QueryModeCoordinates:
emit _parseCoordinateData(jsonData); emit _parseCoordinateData(jsonData);
...@@ -227,7 +227,6 @@ TerrainAtCoordinateBatchManager::TerrainAtCoordinateBatchManager(void) ...@@ -227,7 +227,6 @@ TerrainAtCoordinateBatchManager::TerrainAtCoordinateBatchManager(void)
void TerrainAtCoordinateBatchManager::addQuery(TerrainAtCoordinateQuery* terrainAtCoordinateQuery, const QList<QGeoCoordinate>& coordinates) void TerrainAtCoordinateBatchManager::addQuery(TerrainAtCoordinateQuery* terrainAtCoordinateQuery, const QList<QGeoCoordinate>& coordinates)
{ {
if (coordinates.length() > 0) { if (coordinates.length() > 0) {
qCDebug(TerrainQueryLog) << "addQuery: TerrainAtCoordinateQuery:coordinates.count" << terrainAtCoordinateQuery << coordinates.count();
connect(terrainAtCoordinateQuery, &TerrainAtCoordinateQuery::destroyed, this, &TerrainAtCoordinateBatchManager::_queryObjectDestroyed); connect(terrainAtCoordinateQuery, &TerrainAtCoordinateQuery::destroyed, this, &TerrainAtCoordinateBatchManager::_queryObjectDestroyed);
QueuedRequestInfo_t queuedRequestInfo = { terrainAtCoordinateQuery, coordinates }; QueuedRequestInfo_t queuedRequestInfo = { terrainAtCoordinateQuery, coordinates };
_requestQueue.append(queuedRequestInfo); _requestQueue.append(queuedRequestInfo);
...@@ -255,14 +254,18 @@ void TerrainAtCoordinateBatchManager::_sendNextBatch(void) ...@@ -255,14 +254,18 @@ void TerrainAtCoordinateBatchManager::_sendNextBatch(void)
// Convert coordinates to point strings for json query // Convert coordinates to point strings for json query
QList<QGeoCoordinate> coords; QList<QGeoCoordinate> coords;
int requestQueueAdded = 0;
foreach (const QueuedRequestInfo_t& requestInfo, _requestQueue) { foreach (const QueuedRequestInfo_t& requestInfo, _requestQueue) {
SentRequestInfo_t sentRequestInfo = { requestInfo.terrainAtCoordinateQuery, false, requestInfo.coordinates.count() }; SentRequestInfo_t sentRequestInfo = { requestInfo.terrainAtCoordinateQuery, false, requestInfo.coordinates.count() };
qCDebug(TerrainQueryLog) << "Building request: coordinate count" << requestInfo.coordinates.count();
_sentRequests.append(sentRequestInfo); _sentRequests.append(sentRequestInfo);
coords += requestInfo.coordinates; coords += requestInfo.coordinates;
requestQueueAdded++;
if (coords.count() > 50) {
break;
}
} }
_requestQueue.clear(); qCDebug(TerrainQueryLog) << "Built request: coordinate count" << coords.count();
_requestQueue = _requestQueue.mid(requestQueueAdded);
_terrainQuery.requestCoordinateHeights(coords); _terrainQuery.requestCoordinateHeights(coords);
_state = State::Downloading; _state = State::Downloading;
......
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