Unverified Commit 5e705032 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #6237 from DonLakeFlyer/CorridorTerrain

Corridor Scan Terrain: Add support for max rates and tolerance
parents 32b4b1da 7973c6b3
...@@ -48,33 +48,9 @@ CorridorScanComplexItem::CorridorScanComplexItem(Vehicle* vehicle, QObject* pare ...@@ -48,33 +48,9 @@ CorridorScanComplexItem::CorridorScanComplexItem(Vehicle* vehicle, QObject* pare
connect(&_cameraCalc, &CameraCalc::distanceToSurfaceRelativeChanged, this, &CorridorScanComplexItem::exitCoordinateHasRelativeAltitudeChanged); connect(&_cameraCalc, &CameraCalc::distanceToSurfaceRelativeChanged, this, &CorridorScanComplexItem::exitCoordinateHasRelativeAltitudeChanged);
connect(&_corridorPolyline, &QGCMapPolyline::dirtyChanged, this, &CorridorScanComplexItem::_polylineDirtyChanged); connect(&_corridorPolyline, &QGCMapPolyline::dirtyChanged, this, &CorridorScanComplexItem::_polylineDirtyChanged);
connect(&_corridorPolyline, &QGCMapPolyline::countChanged, this, &CorridorScanComplexItem::_polylineCountChanged);
connect(&_corridorPolyline, &QGCMapPolyline::pathChanged, this, &CorridorScanComplexItem::_rebuildCorridor); connect(&_corridorPolyline, &QGCMapPolyline::pathChanged, this, &CorridorScanComplexItem::_rebuildCorridorPolygon);
connect(&_corridorWidthFact, &Fact::valueChanged, this, &CorridorScanComplexItem::_rebuildCorridor); connect(&_corridorWidthFact, &Fact::valueChanged, this, &CorridorScanComplexItem::_rebuildCorridorPolygon);
_rebuildCorridor();
}
void CorridorScanComplexItem::_polylineCountChanged(int count)
{
Q_UNUSED(count);
emit lastSequenceNumberChanged(lastSequenceNumber());
}
int CorridorScanComplexItem::lastSequenceNumber(void) const
{
int itemCount = _transectPoints.count(); // Each transpect point represents a waypoint item
if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) {
// Only one camera start and on camera stop
itemCount += 2;
} else {
// Each transect will have a camera start and stop in it
itemCount += _transectCount() * 2;
}
return _sequenceNumber + itemCount - 1;
} }
void CorridorScanComplexItem::save(QJsonArray& planItems) void CorridorScanComplexItem::save(QJsonArray& planItems)
...@@ -147,7 +123,7 @@ bool CorridorScanComplexItem::load(const QJsonObject& complexObject, int sequenc ...@@ -147,7 +123,7 @@ bool CorridorScanComplexItem::load(const QJsonObject& complexObject, int sequenc
_entryPoint = complexObject[_jsonEntryPointKey].toInt(); _entryPoint = complexObject[_jsonEntryPointKey].toInt();
_rebuildCorridor(); _rebuildTransects();
_ignoreRecalc = false; _ignoreRecalc = false;
...@@ -183,58 +159,42 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i ...@@ -183,58 +159,42 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
{ {
qCDebug(CorridorScanComplexItemLog) << "_buildAndAppendMissionItems"; qCDebug(CorridorScanComplexItemLog) << "_buildAndAppendMissionItems";
// First adjust for terrain (this will set altitudes into _transectionPoints in all cases
_adjustTransectPointsForTerrain();
// Now build the mission items from the transect points // Now build the mission items from the transect points
MissionItem* item; MissionItem* item;
int seqNum = _sequenceNumber; int seqNum = _sequenceNumber;
bool imagesEverywhere = _cameraTriggerInTurnAroundFact.rawValue().toBool(); bool imagesEverywhere = _cameraTriggerInTurnAroundFact.rawValue().toBool();
bool addTriggerAtBeginning = imagesEverywhere; bool addTriggerAtBeginning = imagesEverywhere;
bool firstPoint = true; bool firstOverallPoint = true;
bool entryPoint = true;
MAV_FRAME mavFrame = followTerrain() || !_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL : MAV_FRAME_GLOBAL_RELATIVE_ALT; MAV_FRAME mavFrame = followTerrain() || !_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL : MAV_FRAME_GLOBAL_RELATIVE_ALT;
foreach (const QVariant& transectPointVar, _transectPoints) { //qDebug() << "_buildAndAppendMissionItems";
QGeoCoordinate transectPoint = transectPointVar.value<QGeoCoordinate>(); foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
bool entryPoint = true;
item = new MissionItem(seqNum++,
MAV_CMD_NAV_WAYPOINT, //qDebug() << "start transect";
mavFrame, foreach (const CoordInfo_t& transectCoordInfo, transect) {
0, // No hold time //qDebug() << transectCoordInfo.coordType;
0.0, // No acceptance radius specified
0.0, // Pass through waypoint
std::numeric_limits<double>::quiet_NaN(), // Yaw unchanged
transectPoint.latitude(),
transectPoint.longitude(),
qAbs(transectPoint.altitude()), // qAbs since negative value indicates survey edge
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
if (firstPoint && addTriggerAtBeginning) {
// Start triggering
addTriggerAtBeginning = false;
item = new MissionItem(seqNum++, item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_CMD_NAV_WAYPOINT,
MAV_FRAME_MISSION, mavFrame,
_cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble(), // trigger distance 0, // No hold time
0, // shutter integration (ignore) 0.0, // No acceptance radius specified
1, // trigger immediately when starting 0.0, // Pass through waypoint
0, 0, 0, 0, // param 4-7 unused std::numeric_limits<double>::quiet_NaN(), // Yaw unchanged
true, // autoContinue transectCoordInfo.coord.latitude(),
false, // isCurrentItem transectCoordInfo.coord.longitude(),
transectCoordInfo.coord.altitude(),
true, // autoContinue
false, // isCurrentItem
missionItemParent); missionItemParent);
items.append(item); items.append(item);
}
firstPoint = false;
if (transectPoint.altitude() < 0 && !imagesEverywhere) { if (firstOverallPoint && addTriggerAtBeginning) {
if (entryPoint) {
// Start triggering // Start triggering
addTriggerAtBeginning = false;
item = new MissionItem(seqNum++, item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION, MAV_FRAME_MISSION,
...@@ -246,21 +206,39 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i ...@@ -246,21 +206,39 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
false, // isCurrentItem false, // isCurrentItem
missionItemParent); missionItemParent);
items.append(item); items.append(item);
} else {
// Stop triggering
item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
0, // stop triggering
0, // shutter integration (ignore)
0, // trigger immediately when starting
0, 0, 0, 0, // param 4-7 unused
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
} }
entryPoint = !entryPoint; firstOverallPoint = false;
if (transectCoordInfo.coordType == TransectStyleComplexItem::CoordTypeSurveyEdge && !imagesEverywhere) {
if (entryPoint) {
// Start of transect, start triggering
item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
_cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble(), // trigger distance
0, // shutter integration (ignore)
1, // trigger immediately when starting
0, 0, 0, 0, // param 4-7 unused
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
} else {
// End of transect, stop triggering
item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
0, // stop triggering
0, // shutter integration (ignore)
0, // trigger immediately when starting
0, 0, 0, 0, // param 4-7 unused
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
}
entryPoint = !entryPoint;
}
} }
} }
...@@ -312,7 +290,7 @@ void CorridorScanComplexItem::rotateEntryPoint(void) ...@@ -312,7 +290,7 @@ void CorridorScanComplexItem::rotateEntryPoint(void)
_entryPoint = 0; _entryPoint = 0;
} }
_rebuildCorridor(); _rebuildTransects();
} }
void CorridorScanComplexItem::_rebuildCorridorPolygon(void) void CorridorScanComplexItem::_rebuildCorridorPolygon(void)
...@@ -349,7 +327,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void) ...@@ -349,7 +327,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
_loadedMissionItemsParent = NULL; _loadedMissionItemsParent = NULL;
} }
_transectPoints.clear(); _transects.clear();
_transectsPathHeightInfo.clear(); _transectsPathHeightInfo.clear();
double transectSpacing = _cameraCalc.adjustedFootprintSide()->rawValue().toDouble(); double transectSpacing = _cameraCalc.adjustedFootprintSide()->rawValue().toDouble();
...@@ -360,8 +338,9 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void) ...@@ -360,8 +338,9 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
if (_corridorPolyline.count() >= 2) { if (_corridorPolyline.count() >= 2) {
// First build up the transects all going the same direction // First build up the transects all going the same direction
QList<QList<QGeoCoordinate>> transects; //qDebug() << "_rebuildTransectsPhase1";
for (int i=0; i<transectCount; i++) { for (int i=0; i<transectCount; i++) {
//qDebug() << "start transect";
double offsetDistance; double offsetDistance;
if (transectCount == 1) { if (transectCount == 1) {
// Single transect is flown over scan line // Single transect is flown over scan line
...@@ -371,24 +350,44 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void) ...@@ -371,24 +350,44 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
offsetDistance = halfWidth - normalizedTransectPosition; offsetDistance = halfWidth - normalizedTransectPosition;
} }
QList<QGeoCoordinate> transect = _corridorPolyline.offsetPolyline(offsetDistance); // Turn transect into CoordInfo transect
transect[0].setAltitude(_surveyEdgeIndicator); QList<TransectStyleComplexItem::CoordInfo_t> transect;
transect[1].setAltitude(_surveyEdgeIndicator); QList<QGeoCoordinate> transectCoords = _corridorPolyline.offsetPolyline(offsetDistance);
for (int j=1; j<transectCoords.count() - 1; j++) {
TransectStyleComplexItem::CoordInfo_t coordInfo = { transectCoords[j], CoordTypeInterior };
transect.append(coordInfo);
}
TransectStyleComplexItem::CoordInfo_t coordInfo = { transectCoords.first(), CoordTypeSurveyEdge };
transect.prepend(coordInfo);
coordInfo = { transectCoords.last(), CoordTypeSurveyEdge };
transect.append(coordInfo);
// Extend the transect ends for turnaround
if (_hasTurnaround()) { if (_hasTurnaround()) {
QGeoCoordinate extensionCoord; QGeoCoordinate turnaroundCoord;
double turnAroundDistance = _turnAroundDistanceFact.rawValue().toDouble();
// Extend the transect ends for turnaround
double azimuth = transect[0].azimuthTo(transect[1]); double azimuth = transectCoords[0].azimuthTo(transectCoords[1]);
extensionCoord = transect[0].atDistanceAndAzimuth(-_turnAroundDistanceFact.rawValue().toDouble(), azimuth); turnaroundCoord = transectCoords[0].atDistanceAndAzimuth(-turnAroundDistance, azimuth);
extensionCoord.setAltitude(qQNaN()); turnaroundCoord.setAltitude(qQNaN());
transect.prepend(extensionCoord); TransectStyleComplexItem::CoordInfo_t coordInfo = { turnaroundCoord, CoordTypeTurnaround };
azimuth = transect.last().azimuthTo(transect[transect.count() - 2]); transect.prepend(coordInfo);
extensionCoord = transect.last().atDistanceAndAzimuth(-_turnAroundDistanceFact.rawValue().toDouble(), azimuth);
extensionCoord.setAltitude(qQNaN()); azimuth = transectCoords.last().azimuthTo(transectCoords[transectCoords.count() - 2]);
transect.append(extensionCoord); turnaroundCoord = transectCoords.last().atDistanceAndAzimuth(-turnAroundDistance, azimuth);
turnaroundCoord.setAltitude(qQNaN());
coordInfo = { turnaroundCoord, CoordTypeTurnaround };
transect.append(coordInfo);
}
#if 0
qDebug() << "transect debug";
foreach (const TransectStyleComplexItem::CoordInfo_t& coordInfo, transect) {
qDebug() << coordInfo.coordType;
} }
#endif
transects.append(transect); _transects.append(transect);
normalizedTransectPosition += transectSpacing; normalizedTransectPosition += transectSpacing;
} }
...@@ -419,30 +418,30 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void) ...@@ -419,30 +418,30 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
break; break;
} }
if (reverseTransects) { if (reverseTransects) {
QList<QList<QGeoCoordinate>> reversedTransects; QList<QList<TransectStyleComplexItem::CoordInfo_t>> reversedTransects;
foreach (const QList<QGeoCoordinate>& transect, transects) { foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
reversedTransects.prepend(transect); reversedTransects.prepend(transect);
} }
transects = reversedTransects; _transects = reversedTransects;
} }
if (reverseVertices) { if (reverseVertices) {
for (int i=0; i<transects.count(); i++) { for (int i=0; i<_transects.count(); i++) {
QList<QGeoCoordinate> reversedVertices; QList<TransectStyleComplexItem::CoordInfo_t> reversedVertices;
foreach (const QGeoCoordinate& vertex, transects[i]) { foreach (const TransectStyleComplexItem::CoordInfo_t& vertex, _transects[i]) {
reversedVertices.prepend(vertex); reversedVertices.prepend(vertex);
} }
transects[i] = reversedVertices; _transects[i] = reversedVertices;
} }
} }
// Convert the list of transects to grid points // Adjust to lawnmower pattern
reverseVertices = false; reverseVertices = false;
for (int i=0; i<transects.count(); i++) { for (int i=0; i<_transects.count(); i++) {
// We must reverse the vertices for every other transect in order to make a lawnmower pattern // We must reverse the vertices for every other transect in order to make a lawnmower pattern
QList<QGeoCoordinate> transectVertices = transects[i]; QList<TransectStyleComplexItem::CoordInfo_t> transectVertices = _transects[i];
if (reverseVertices) { if (reverseVertices) {
reverseVertices = false; reverseVertices = false;
QList<QGeoCoordinate> reversedVertices; QList<TransectStyleComplexItem::CoordInfo_t> reversedVertices;
for (int j=transectVertices.count()-1; j>=0; j--) { for (int j=transectVertices.count()-1; j>=0; j--) {
reversedVertices.append(transectVertices[j]); reversedVertices.append(transectVertices[j]);
} }
...@@ -450,23 +449,17 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void) ...@@ -450,23 +449,17 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
} else { } else {
reverseVertices = true; reverseVertices = true;
} }
for (int i=0; i<transectVertices.count(); i++) { _transects[i] = transectVertices;
_transectPoints.append(QVariant::fromValue((transectVertices[i])));
}
normalizedTransectPosition += transectSpacing;
} }
} }
_queryTransectsPathHeightInfo();
} }
void CorridorScanComplexItem::_rebuildTransectsPhase2(void) void CorridorScanComplexItem::_rebuildTransectsPhase2(void)
{ {
// Calculate distance flown for complex item // Calculate distance flown for complex item
_complexDistance = 0; _complexDistance = 0;
for (int i=0; i<_transectPoints.count() - 2; i++) { for (int i=0; i<_visualTransectPoints.count() - 2; i++) {
_complexDistance += _transectPoints[i].value<QGeoCoordinate>().distanceTo(_transectPoints[i+1].value<QGeoCoordinate>()); _complexDistance += _visualTransectPoints[i].value<QGeoCoordinate>().distanceTo(_visualTransectPoints[i+1].value<QGeoCoordinate>());
} }
if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) { if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) {
...@@ -476,23 +469,15 @@ void CorridorScanComplexItem::_rebuildTransectsPhase2(void) ...@@ -476,23 +469,15 @@ void CorridorScanComplexItem::_rebuildTransectsPhase2(void)
_cameraShots = singleTransectImageCount * _transectCount(); _cameraShots = singleTransectImageCount * _transectCount();
} }
_coordinate = _transectPoints.count() ? _transectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate(); _coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate();
_exitCoordinate = _transectPoints.count() ? _transectPoints.last().value<QGeoCoordinate>() : QGeoCoordinate(); _exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value<QGeoCoordinate>() : QGeoCoordinate();
emit transectPointsChanged();
emit cameraShotsChanged(); emit cameraShotsChanged();
emit complexDistanceChanged(); emit complexDistanceChanged();
emit coordinateChanged(_coordinate); emit coordinateChanged(_coordinate);
emit exitCoordinateChanged(_exitCoordinate); emit exitCoordinateChanged(_exitCoordinate);
} }
void CorridorScanComplexItem::_rebuildCorridor(void)
{
_rebuildCorridorPolygon();
_rebuildTransectsPhase1();
_rebuildTransectsPhase2();
}
bool CorridorScanComplexItem::readyForSave(void) const bool CorridorScanComplexItem::readyForSave(void) const
{ {
return TransectStyleComplexItem::readyForSave(); return TransectStyleComplexItem::readyForSave();
......
...@@ -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,11 +175,38 @@ void CorridorScanComplexItemTest::_testItemCount(void) ...@@ -153,11 +175,38 @@ void CorridorScanComplexItemTest::_testItemCount(void)
QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber()); QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
items.clear(); items.clear();
#if 0
// Terrain queries seem to take random amount of time so these don't work 100%
_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();
#endif
} }
void CorridorScanComplexItemTest::_testPathChanges(void) void CorridorScanComplexItemTest::_testPathChanges(void)
......
...@@ -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,
......
...@@ -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;
......
...@@ -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)
......
...@@ -36,8 +36,7 @@ const char* TransectStyleComplexItem::_jsonTransectPointsKey = "Tra ...@@ -36,8 +36,7 @@ const char* TransectStyleComplexItem::_jsonTransectPointsKey = "Tra
const char* TransectStyleComplexItem::_jsonItemsKey = "Items"; const char* TransectStyleComplexItem::_jsonItemsKey = "Items";
const char* TransectStyleComplexItem::_jsonFollowTerrainKey = "FollowTerrain"; const char* TransectStyleComplexItem::_jsonFollowTerrainKey = "FollowTerrain";
const int TransectStyleComplexItem::_terrainQueryTimeoutMsecs = 500; const int TransectStyleComplexItem::_terrainQueryTimeoutMsecs = 1000;
const double TransectStyleComplexItem::_surveyEdgeIndicator = -10;
TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, QString settingsGroup, QObject* parent) TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, QString settingsGroup, QObject* parent)
: ComplexMissionItem (vehicle, parent) : ComplexMissionItem (vehicle, parent)
...@@ -77,18 +76,6 @@ TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, QString set ...@@ -77,18 +76,6 @@ TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, QString set
connect(_cameraCalc.adjustedFootprintSide(), &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects); connect(_cameraCalc.adjustedFootprintSide(), &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
connect(_cameraCalc.adjustedFootprintFrontal(), &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects); connect(_cameraCalc.adjustedFootprintFrontal(), &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
connect(&_cameraTriggerInTurnAroundFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
connect(_cameraCalc.adjustedFootprintSide(), &Fact::valueChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
connect(_cameraCalc.adjustedFootprintFrontal(), &Fact::valueChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
connect(this, &TransectStyleComplexItem::followTerrainChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
connect(&_terrainAdjustMaxClimbRateFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
connect(&_terrainAdjustMaxDescentRateFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
connect(&_terrainAdjustToleranceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged); connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged); connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged); connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
...@@ -114,8 +101,8 @@ TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, QString set ...@@ -114,8 +101,8 @@ TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, QString set
connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::coveredAreaChanged); connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::coveredAreaChanged);
connect(this, &TransectStyleComplexItem::transectPointsChanged, this, &TransectStyleComplexItem::complexDistanceChanged); connect(this, &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
connect(this, &TransectStyleComplexItem::transectPointsChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged); connect(this, &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
} }
void TransectStyleComplexItem::_setCameraShots(int cameraShots) void TransectStyleComplexItem::_setCameraShots(int cameraShots)
...@@ -162,7 +149,7 @@ void TransectStyleComplexItem::_save(QJsonObject& complexObject) ...@@ -162,7 +149,7 @@ void TransectStyleComplexItem::_save(QJsonObject& complexObject)
QJsonValue transectPointsJson; QJsonValue transectPointsJson;
// Save transects polyline // Save transects polyline
JsonHelper::saveGeoCoordinateArray(_transectPoints, false /* writeAltitude */, transectPointsJson); JsonHelper::saveGeoCoordinateArray(_visualTransectPoints, false /* writeAltitude */, transectPointsJson);
innerObject[_jsonTransectPointsKey] = transectPointsJson; innerObject[_jsonTransectPointsKey] = transectPointsJson;
// Save the interal mission items // Save the interal mission items
...@@ -226,10 +213,13 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString& ...@@ -226,10 +213,13 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString&
return false; return false;
} }
#if 0
// FIXME
// Load transect points // Load transect points
if (!JsonHelper::loadGeoCoordinateArray(innerObject[_jsonTransectPointsKey], false /* altitudeRequired */, _transectPoints, errorString)) { if (!JsonHelper::loadGeoCoordinateArray(innerObject[_jsonTransectPointsKey], false /* altitudeRequired */, _transectPoints, errorString)) {
return false; return false;
} }
#endif
// Load generated mission items // Load generated mission items
_loadedMissionItemsParent = new QObject(this); _loadedMissionItemsParent = new QObject(this);
...@@ -277,8 +267,8 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString& ...@@ -277,8 +267,8 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString&
double TransectStyleComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const double TransectStyleComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const
{ {
double greatestDistance = 0.0; double greatestDistance = 0.0;
for (int i=0; i<_transectPoints.count(); i++) { for (int i=0; i<_visualTransectPoints.count(); i++) {
QGeoCoordinate vertex = _transectPoints[i].value<QGeoCoordinate>(); QGeoCoordinate vertex = _visualTransectPoints[i].value<QGeoCoordinate>();
double distance = vertex.distanceTo(other); double distance = vertex.distanceTo(other);
if (distance > greatestDistance) { if (distance > greatestDistance) {
greatestDistance = distance; greatestDistance = distance;
...@@ -327,11 +317,6 @@ void TransectStyleComplexItem::_updateCoordinateAltitudes(void) ...@@ -327,11 +317,6 @@ void TransectStyleComplexItem::_updateCoordinateAltitudes(void)
emit exitCoordinateChanged(exitCoordinate()); emit exitCoordinateChanged(exitCoordinate());
} }
void TransectStyleComplexItem::_signalLastSequenceNumberChanged(void)
{
emit lastSequenceNumberChanged(lastSequenceNumber());
}
double TransectStyleComplexItem::coveredArea(void) const double TransectStyleComplexItem::coveredArea(void) const
{ {
return _surveyAreaPolygon.area(); return _surveyAreaPolygon.area();
...@@ -355,7 +340,21 @@ bool TransectStyleComplexItem::hoverAndCaptureAllowed(void) const ...@@ -355,7 +340,21 @@ bool TransectStyleComplexItem::hoverAndCaptureAllowed(void) const
void TransectStyleComplexItem::_rebuildTransects(void) void TransectStyleComplexItem::_rebuildTransects(void)
{ {
_rebuildTransectsPhase1(); _rebuildTransectsPhase1();
_queryTransectsPathHeightInfo();
// Generate the visuals transect representation
_visualTransectPoints.clear();
foreach (const QList<CoordInfo_t>& transect, _transects) {
foreach (const CoordInfo_t& coordInfo, transect) {
_visualTransectPoints.append(QVariant::fromValue(coordInfo.coord));
}
}
emit visualTransectPointsChanged();
_rebuildTransectsPhase2(); _rebuildTransectsPhase2();
emit lastSequenceNumberChanged(lastSequenceNumber());
} }
void TransectStyleComplexItem::_queryTransectsPathHeightInfo(void) void TransectStyleComplexItem::_queryTransectsPathHeightInfo(void)
...@@ -367,89 +366,104 @@ void TransectStyleComplexItem::_queryTransectsPathHeightInfo(void) ...@@ -367,89 +366,104 @@ void TransectStyleComplexItem::_queryTransectsPathHeightInfo(void)
_terrainPolyPathQuery = NULL; _terrainPolyPathQuery = NULL;
} }
if (_transectPoints.count() > 1) { if (_transects.count()) {
// We don't actually send the query until this timer times out. This way we only send // 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. // the latest request if we get a bunch in a row.
_terrainQueryTimer.start(); _terrainQueryTimer.start();
} }
} }
void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void) void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void)
{ {
if (_transectPoints.count() > 1) { // Append all transects into a single PolyPath query
QList<QGeoCoordinate> transectPoints;
foreach (const QList<CoordInfo_t>& transect, _transects) {
foreach (const CoordInfo_t& coordInfo, transect) {
transectPoints.append(coordInfo.coord);
}
}
if (transectPoints.count() > 1) {
_terrainPolyPathQuery = new TerrainPolyPathQuery(this); _terrainPolyPathQuery = new TerrainPolyPathQuery(this);
connect(_terrainPolyPathQuery, &TerrainPolyPathQuery::terrainData, this, &TransectStyleComplexItem::_polyPathTerrainData); connect(_terrainPolyPathQuery, &TerrainPolyPathQuery::terrainData, this, &TransectStyleComplexItem::_polyPathTerrainData);
_terrainPolyPathQuery->requestData(_transectPoints); _terrainPolyPathQuery->requestData(transectPoints);
} }
} }
void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList<TerrainPathQuery::PathHeightInfo_t>& rgPathHeightInfo) void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList<TerrainPathQuery::PathHeightInfo_t>& rgPathHeightInfo)
{ {
_transectsPathHeightInfo.clear();
if (success) { if (success) {
_transectsPathHeightInfo = rgPathHeightInfo; // Break out into individual transects
} else { int pathHeightIndex = 0;
_transectsPathHeightInfo.clear(); for (int i=0; i<_transects.count(); i++) {
_transectsPathHeightInfo.append(QList<TerrainPathQuery::PathHeightInfo_t>());
int cPathHeight = _transects[i].count() - 1;
while (cPathHeight-- > 0) {
_transectsPathHeightInfo[i].append(rgPathHeightInfo[pathHeightIndex++]);
}
pathHeightIndex++; // There is an extra on between each transect
}
// Now that we have terrain data we can adjust
_adjustTransectsForTerrain();
} }
} }
bool TransectStyleComplexItem::readyForSave(void) const bool TransectStyleComplexItem::readyForSave(void) const
{ {
// Make sure we have the terrain data we need // Make sure we have the terrain data we need
return _transectPoints.count() > 1 ? _transectsPathHeightInfo.count() : false; return _followTerrain ? _transectsPathHeightInfo.count() : true;
} }
/// Add altitude values to the standard transect points (whether following terrain or not) void TransectStyleComplexItem::_adjustTransectsForTerrain(void)
void TransectStyleComplexItem::_adjustTransectPointsForTerrain(void)
{ {
if (_followTerrain && !readyForSave()) { if (_followTerrain) {
qCWarning(TransectStyleComplexItemLog) << "_adjustTransectPointsForTerrain called when terrain data not ready"; if (!readyForSave()) {
qgcApp()->showMessage(tr("INTERNAL ERROR: TransectStyleComplexItem::_adjustTransectPointsForTerrain called when terrain data not ready. Plan will be incorrect.")); qCWarning(TransectStyleComplexItemLog) << "_adjustTransectPointsForTerrain called when terrain data not ready";
return; qgcApp()->showMessage(tr("INTERNAL ERROR: TransectStyleComplexItem::_adjustTransectPointsForTerrain called when terrain data not ready. Plan will be incorrect."));
} return;
}
double requestedAltitude = _cameraCalc.distanceToSurface()->rawValue().toDouble();
qDebug() << _transectPoints.count() << _transectsPathHeightInfo.count();
for (int i=0; i<_transectPoints.count() - 1; i++) {
QGeoCoordinate transectPoint = _transectPoints[i].value<QGeoCoordinate>();
bool surveyEdgeIndicator = transectPoint.altitude() == _surveyEdgeIndicator; // First step is add all interstitial points at max resolution
if (_followTerrain) { for (int i=0; i<_transects.count(); i++) {
transectPoint.setAltitude(_transectsPathHeightInfo[i].heights[0] + requestedAltitude); _addInterstitialTerrainPoints(_transects[i], _transectsPathHeightInfo[i]);
} else {
transectPoint.setAltitude(requestedAltitude);
} }
if (surveyEdgeIndicator) {
// Use to indicate survey edge for (int i=0; i<_transects.count(); i++) {
transectPoint.setAltitude(-transectPoint.altitude()); _adjustForMaxRates(_transects[i]);
} }
_transectPoints[i] = QVariant::fromValue(transectPoint); for (int i=0; i<_transects.count(); i++) {
} _adjustForTolerance(_transects[i]);
}
// Take care of last point emit lastSequenceNumberChanged(lastSequenceNumber());
QGeoCoordinate transectPoint = _transectPoints.last().value<QGeoCoordinate>();
bool surveyEdgeIndicator = transectPoint.altitude() == _surveyEdgeIndicator;
if (_followTerrain){
transectPoint.setAltitude(_transectsPathHeightInfo.last().heights.last() + requestedAltitude);
} else { } else {
transectPoint.setAltitude(requestedAltitude); // Not following terrain show just add requested altitude to coords
} double requestedAltitude = _cameraCalc.distanceToSurface()->rawValue().toDouble();
if (surveyEdgeIndicator) {
// Use to indicate survey edge for (int i=0; i<_transects.count(); i++) {
transectPoint.setAltitude(-transectPoint.altitude()); QList<CoordInfo_t>& transect = _transects[i];
}
_transectPoints[_transectPoints.count() - 1] = QVariant::fromValue(transectPoint);
_addInterstitialTransectsForTerrain(); for (int j=0; j<transect.count(); j++) {
QGeoCoordinate& coord = transect[j].coord;
coord.setAltitude(requestedAltitude);
}
}
}
} }
/// Returns the altitude in between the two points on a line. /// Returns the altitude in between the two points on a line.
/// @param precentTowardsTo Example: .25 = twenty five percent along the distance of from to to /// @param precentTowardsTo Example: .25 = twenty five percent along the distance of from to to
double TransectStyleComplexItem::_altitudeBetweenCoords(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord, double percentTowardsTo) double TransectStyleComplexItem::_altitudeBetweenCoords(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord, double percentTowardsTo)
{ {
double fromAlt = qAbs(fromCoord.altitude()); double fromAlt = fromCoord.altitude();
double toAlt = qAbs(toCoord.altitude()); double toAlt = toCoord.altitude();
double altDiff = toAlt - fromAlt; double altDiff = toAlt - fromAlt;
return fromAlt + (altDiff * percentTowardsTo); return fromAlt + (altDiff * percentTowardsTo);
} }
...@@ -483,55 +497,146 @@ int TransectStyleComplexItem::_maxPathHeight(const TerrainPathQuery::PathHeightI ...@@ -483,55 +497,146 @@ int TransectStyleComplexItem::_maxPathHeight(const TerrainPathQuery::PathHeightI
return maxIndex; return maxIndex;
} }
/// Add points in between existing points to account for terrain void TransectStyleComplexItem::_adjustForMaxRates(QList<CoordInfo_t>& transect)
void TransectStyleComplexItem::_addInterstitialTransectsForTerrain(void)
{ {
if (!_followTerrain) { double maxClimbRate = _terrainAdjustMaxClimbRateFact.rawValue().toDouble();
double maxDescentRate = -_terrainAdjustMaxDescentRateFact.rawValue().toDouble();
double flightSpeed = _missionFlightStatus.vehicleSpeed;
if (qIsNaN(flightSpeed) || (maxClimbRate == 0 && maxDescentRate == 0)) {
if (qIsNaN(flightSpeed)) {
qWarning() << "TransectStyleComplexItem::_adjustForMaxRates called with flightSpeed = NaN";
}
return; return;
} }
double requestedAltitude = _cameraCalc.distanceToSurface()->rawValue().toDouble(); // Adjust climb rates
bool climbRateAdjusted;
do {
//qDebug() << "climbrate pass";
climbRateAdjusted = false;
for (int i=0; i<transect.count() - 1; i++) {
QGeoCoordinate& fromCoord = transect[i].coord;
QGeoCoordinate& toCoord = transect[i+1].coord;
double altDifference = toCoord.altitude() - fromCoord.altitude();
double distance = fromCoord.distanceTo(toCoord);
double seconds = distance / flightSpeed;
double climbRate = altDifference / seconds;
//qDebug() << QString("Index:%1 altDifference:%2 distance:%3 seconds:%4 climbRate:%5").arg(i).arg(altDifference).arg(distance).arg(seconds).arg(climbRate);
if (climbRate > 0 && climbRate - maxClimbRate > 0.1) {
double maxAltitudeDelta = maxClimbRate * seconds;
fromCoord.setAltitude(toCoord.altitude() - maxAltitudeDelta);
//qDebug() << "Adjusting";
climbRateAdjusted = true;
}
}
} while (climbRateAdjusted);
// Adjust descent rates
bool descentRateAdjusted;
do {
//qDebug() << "descent rate pass";
descentRateAdjusted = false;
for (int i=1; i<transect.count(); i++) {
QGeoCoordinate& fromCoord = transect[i-1].coord;
QGeoCoordinate& toCoord = transect[i].coord;
double altDifference = toCoord.altitude() - fromCoord.altitude();
double distance = fromCoord.distanceTo(toCoord);
double seconds = distance / flightSpeed;
double descentRate = altDifference / seconds;
//qDebug() << QString("Index:%1 altDifference:%2 distance:%3 seconds:%4 descentRate:%5").arg(i).arg(altDifference).arg(distance).arg(seconds).arg(descentRate);
if (descentRate < 0 && descentRate - maxDescentRate < -0.1) {
double maxAltitudeDelta = maxDescentRate * seconds;
toCoord.setAltitude(fromCoord.altitude() + maxAltitudeDelta);
//qDebug() << "Adjusting";
descentRateAdjusted = true;
}
}
} while (descentRateAdjusted);
}
void TransectStyleComplexItem::_adjustForTolerance(QList<CoordInfo_t>& transect)
{
QList<CoordInfo_t> adjustedPoints;
double tolerance = _terrainAdjustToleranceFact.rawValue().toDouble(); double tolerance = _terrainAdjustToleranceFact.rawValue().toDouble();
QList<QVariant> terrainAdjustedTransectPoints;
// Check for needed terrain adjust in between the transect points int coordIndex = 0;
for (int i=0; i<_transectPoints.count() - 1; i++) { while (coordIndex < transect.count()) {
terrainAdjustedTransectPoints.append(_transectPoints[i]); const CoordInfo_t& fromCoordInfo = transect[coordIndex];
QGeoCoordinate fromCoord = _transectPoints[i].value<QGeoCoordinate>(); adjustedPoints.append(fromCoordInfo);
QGeoCoordinate toCoord = _transectPoints[i+1].value<QGeoCoordinate>();
const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo = _transectsPathHeightInfo[i]; // Walk forward until we fall out of tolerence or find a fixed point
int cHeights = pathHeightInfo.heights.count(); while (++coordIndex < transect.count()) {
int lastAddedHeightIndex = 0; const CoordInfo_t& toCoordInfo = transect[coordIndex];
//qDebug() << "cHeights" << cHeights << pathHeightInfo.heights; if (toCoordInfo.coordType != CoordTypeInteriorTerrainAdded || qAbs(fromCoordInfo.coord.altitude() - toCoordInfo.coord.altitude()) > tolerance) {
adjustedPoints.append(toCoordInfo);
coordIndex++;
break;
}
}
}
#if 0
qDebug() << "_adjustForTolerance";
foreach (const TransectStyleComplexItem::CoordInfo_t& coordInfo, adjustedPoints) {
qDebug() << coordInfo.coordType;
}
#endif
transect = adjustedPoints;
}
void TransectStyleComplexItem::_addInterstitialTerrainPoints(QList<CoordInfo_t>& transect, const QList<TerrainPathQuery::PathHeightInfo_t>& transectPathHeightInfo)
{
QList<CoordInfo_t> adjustedTransect;
adjustedTransect.append(transect.first());
for (int i=0; i<transect.count() - 1; i++) {
CoordInfo_t fromCoordInfo = transect[i];
CoordInfo_t toCoordInfo = transect[i+1];
for (int pathHeightIndex=1; pathHeightIndex<pathHeightInfo.heights.count() - 2; pathHeightIndex++) { double azimuth = fromCoordInfo.coord.azimuthTo(toCoordInfo.coord);
double distance = fromCoordInfo.coord.distanceTo(toCoordInfo.coord);
const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo = transectPathHeightInfo[i];
double requestedAltitude = _cameraCalc.distanceToSurface()->rawValue().toDouble();
fromCoordInfo.coord.setAltitude(pathHeightInfo.heights.first() + requestedAltitude);
toCoordInfo.coord.setAltitude(pathHeightInfo.heights.last() + requestedAltitude);
int cHeights = pathHeightInfo.heights.count();
for (int pathHeightIndex=1; pathHeightIndex<cHeights - 1; pathHeightIndex++) {
double interstitialTerrainHeight = pathHeightInfo.heights[pathHeightIndex]; double interstitialTerrainHeight = pathHeightInfo.heights[pathHeightIndex];
double percentTowardsTo = (1.0 / (cHeights - lastAddedHeightIndex)) * (pathHeightIndex - lastAddedHeightIndex); double percentTowardsTo = (1.0 / (cHeights - 1)) * pathHeightIndex;
double interstitialHeight = _altitudeBetweenCoords(fromCoord, toCoord, percentTowardsTo);
CoordInfo_t interstitialCoordInfo;
double interstitialDeltaOverTerrain = interstitialHeight - interstitialTerrainHeight; interstitialCoordInfo.coordType = CoordTypeInteriorTerrainAdded;
double requestedDeltaOverTerrain = requestedAltitude; interstitialCoordInfo.coord = fromCoordInfo.coord.atDistanceAndAzimuth(distance * percentTowardsTo, azimuth);
interstitialCoordInfo.coord.setAltitude(interstitialTerrainHeight + requestedAltitude);
//qDebug() << "interstitialDeltaOverTerrain:requestedDeltaOverTerrain" << interstitialDeltaOverTerrain << requestedDeltaOverTerrain;
adjustedTransect.append(interstitialCoordInfo);
if (qAbs(requestedDeltaOverTerrain - interstitialDeltaOverTerrain) > tolerance) {
// We need to add a new point to adjust for terrain
double azimuth = fromCoord.azimuthTo(toCoord);
double distance = fromCoord.distanceTo(toCoord);
QGeoCoordinate interstitialCoord = fromCoord.atDistanceAndAzimuth(distance * percentTowardsTo, azimuth);
interstitialCoord.setAltitude(interstitialTerrainHeight + requestedAltitude);
terrainAdjustedTransectPoints.append(QVariant::fromValue(interstitialCoord));
fromCoord = interstitialCoord;
lastAddedHeightIndex = pathHeightIndex;
//qDebug() << "Added index" << terrainAdjustedTransectPoints.count() - 1;
}
} }
adjustedTransect.append(toCoordInfo);
}
#if 0
qDebug() << "_addInterstitialTerrainPoints";
foreach (const TransectStyleComplexItem::CoordInfo_t& coordInfo, adjustedTransect) {
qDebug() << coordInfo.coordType;
} }
terrainAdjustedTransectPoints.append(_transectPoints.last()); #endif
_transectPoints = terrainAdjustedTransectPoints; transect = adjustedTransect;
} }
void TransectStyleComplexItem::setFollowTerrain(bool followTerrain) void TransectStyleComplexItem::setFollowTerrain(bool followTerrain)
...@@ -541,3 +646,23 @@ void TransectStyleComplexItem::setFollowTerrain(bool followTerrain) ...@@ -541,3 +646,23 @@ void TransectStyleComplexItem::setFollowTerrain(bool followTerrain)
emit followTerrainChanged(followTerrain); emit followTerrainChanged(followTerrain);
} }
} }
int TransectStyleComplexItem::lastSequenceNumber(void) const
{
int itemCount = 0;
foreach (const QList<CoordInfo_t>& rgCoordInfo, _transects) {
itemCount += rgCoordInfo.count();
}
if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) {
// Only one camera start and on camera stop
itemCount += 2;
} else {
// Each transect will have a camera start and stop in it
itemCount += _transects.count() * 2;
}
return _sequenceNumber + itemCount - 1;
}
...@@ -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);
}; };
...@@ -31,7 +31,7 @@ void TransectStyleComplexItemTest::init(void) ...@@ -31,7 +31,7 @@ void TransectStyleComplexItemTest::init(void)
_rgSignals[cameraShotsChangedIndex] = SIGNAL(cameraShotsChanged()); _rgSignals[cameraShotsChangedIndex] = SIGNAL(cameraShotsChanged());
_rgSignals[timeBetweenShotsChangedIndex] = SIGNAL(timeBetweenShotsChanged()); _rgSignals[timeBetweenShotsChangedIndex] = SIGNAL(timeBetweenShotsChanged());
_rgSignals[cameraMinTriggerIntervalChangedIndex] = SIGNAL(cameraMinTriggerIntervalChanged(double)); _rgSignals[cameraMinTriggerIntervalChangedIndex] = SIGNAL(cameraMinTriggerIntervalChanged(double));
_rgSignals[transectPointsChangedIndex] = SIGNAL(transectPointsChanged()); _rgSignals[visualTransectPointsChangedIndex] = SIGNAL(visualTransectPointsChanged());
_rgSignals[coveredAreaChangedIndex] = SIGNAL(coveredAreaChanged()); _rgSignals[coveredAreaChangedIndex] = SIGNAL(coveredAreaChanged());
_rgSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool)); _rgSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_rgSignals[complexDistanceChangedIndex] = SIGNAL(complexDistanceChanged()); _rgSignals[complexDistanceChangedIndex] = SIGNAL(complexDistanceChanged());
......
...@@ -42,7 +42,7 @@ private: ...@@ -42,7 +42,7 @@ private:
cameraShotsChangedIndex = 0, cameraShotsChangedIndex = 0,
timeBetweenShotsChangedIndex, timeBetweenShotsChangedIndex,
cameraMinTriggerIntervalChangedIndex, cameraMinTriggerIntervalChangedIndex,
transectPointsChangedIndex, visualTransectPointsChangedIndex,
coveredAreaChangedIndex, coveredAreaChangedIndex,
// These signals are from ComplexItem // These signals are from ComplexItem
dirtyChangedIndex, dirtyChangedIndex,
...@@ -56,18 +56,18 @@ private: ...@@ -56,18 +56,18 @@ private:
enum { enum {
// These signals are from TransectStyleComplexItem // These signals are from TransectStyleComplexItem
cameraShotsChangedMask = 1 << cameraShotsChangedIndex, cameraShotsChangedMask = 1 << cameraShotsChangedIndex,
timeBetweenShotsChangedMask = 1 << timeBetweenShotsChangedIndex, timeBetweenShotsChangedMask = 1 << timeBetweenShotsChangedIndex,
cameraMinTriggerIntervalChangedMask = 1 << cameraMinTriggerIntervalChangedIndex, cameraMinTriggerIntervalChangedMask = 1 << cameraMinTriggerIntervalChangedIndex,
transectPointsChangedMask = 1 << transectPointsChangedIndex, visualTransectPointsChangedMask = 1 << visualTransectPointsChangedIndex,
coveredAreaChangedMask = 1 << coveredAreaChangedIndex, coveredAreaChangedMask = 1 << coveredAreaChangedIndex,
// These signals are from ComplexItem // These signals are from ComplexItem
dirtyChangedMask = 1 << dirtyChangedIndex, dirtyChangedMask = 1 << dirtyChangedIndex,
complexDistanceChangedMask = 1 << complexDistanceChangedIndex, complexDistanceChangedMask = 1 << complexDistanceChangedIndex,
greatestDistanceToChangedMask = 1 << greatestDistanceToChangedIndex, greatestDistanceToChangedMask = 1 << greatestDistanceToChangedIndex,
additionalTimeDelayChangedMask = 1 << additionalTimeDelayChangedIndex, additionalTimeDelayChangedMask = 1 << additionalTimeDelayChangedIndex,
// These signals are from VisualMissionItem // These signals are from VisualMissionItem
lastSequenceNumberChangedMask = 1 << lastSequenceNumberChangedIndex, lastSequenceNumberChangedMask = 1 << lastSequenceNumberChangedIndex,
}; };
static const size_t _cSignals = maxSignalIndex; static const size_t _cSignals = maxSignalIndex;
...@@ -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