From 0545246905e86f7e640280494127d89eaec402ff Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Thu, 2 Aug 2018 14:40:50 -0700 Subject: [PATCH 1/3] Use qCWarning for internal errors --- src/TerrainTile.cc | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/TerrainTile.cc b/src/TerrainTile.cc index 9c17ed2..539ae9d 100644 --- a/src/TerrainTile.cc +++ b/src/TerrainTile.cc @@ -134,7 +134,7 @@ TerrainTile::TerrainTile(QByteArray byteArray) bool TerrainTile::isIn(const QGeoCoordinate& coordinate) const { if (!_isValid) { - qCDebug(TerrainTileLog) << "isIn requested, but tile not valid"; + qCWarning(TerrainTileLog) << "isIn requested, but tile not valid"; return false; } bool ret = coordinate.latitude() >= _southWest.latitude() && coordinate.longitude() >= _southWest.longitude() && @@ -157,7 +157,7 @@ double TerrainTile::elevation(const QGeoCoordinate& coordinate) const qCDebug(TerrainTileLog) << "indexLat:indexLon" << indexLat << indexLon << "elevation" << _data[indexLat][indexLon]; return static_cast(_data[indexLat][indexLon]); } else { - qCDebug(TerrainTileLog) << "Asking for elevation, but no valid data."; + qCWarning(TerrainTileLog) << "Asking for elevation, but no valid data."; return -1.0; } } @@ -284,6 +284,7 @@ int TerrainTile::_latToDataIndex(double latitude) const if (isValid() && _southWest.isValid() && _northEast.isValid()) { return qRound((latitude - _southWest.latitude()) / (_northEast.latitude() - _southWest.latitude()) * (_gridSizeLat - 1)); } else { + qCWarning(TerrainTileLog) << "TerrainTile::_latToDataIndex internal error" << isValid() << _southWest.isValid() << _northEast.isValid(); return -1; } } @@ -293,6 +294,7 @@ int TerrainTile::_lonToDataIndex(double longitude) const if (isValid() && _southWest.isValid() && _northEast.isValid()) { return qRound((longitude - _southWest.longitude()) / (_northEast.longitude() - _southWest.longitude()) * (_gridSizeLon - 1)); } else { + qCWarning(TerrainTileLog) << "TerrainTile::_lonToDataIndex internal error" << isValid() << _southWest.isValid() << _northEast.isValid(); return -1; } } From 9b79fbeb7ea43f8d9eefe94993b81558f051616c Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Thu, 2 Aug 2018 14:41:26 -0700 Subject: [PATCH 2/3] Fix failure handling --- src/MissionManager/VisualMissionItem.cc | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/src/MissionManager/VisualMissionItem.cc b/src/MissionManager/VisualMissionItem.cc index 70ccdbc..0370a06 100644 --- a/src/MissionManager/VisualMissionItem.cc +++ b/src/MissionManager/VisualMissionItem.cc @@ -195,9 +195,7 @@ void VisualMissionItem::_reallyUpdateTerrainAltitude(void) void VisualMissionItem::_terrainDataReceived(bool success, QList heights) { - if (success) { - _terrainAltitude = heights[0]; - emit terrainAltitudeChanged(_terrainAltitude); - sender()->deleteLater(); - } + _terrainAltitude = success ? heights[0] : qQNaN(); + emit terrainAltitudeChanged(_terrainAltitude); + sender()->deleteLater(); } From 480da6fc69929a18d62e63105c87e9660b6234a5 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Thu, 2 Aug 2018 14:43:38 -0700 Subject: [PATCH 3/3] Turn internal errors (elevation == -1) into failed query to prevent bogus elevation from reaching upper layers. --- src/Terrain/TerrainQuery.cc | 59 ++++++++++++++++++++++++++++++++++++--------- src/Terrain/TerrainQuery.h | 6 ++--- 2 files changed, 51 insertions(+), 14 deletions(-) diff --git a/src/Terrain/TerrainQuery.cc b/src/Terrain/TerrainQuery.cc index 2f1426a..f64806f 100644 --- a/src/Terrain/TerrainQuery.cc +++ b/src/Terrain/TerrainQuery.cc @@ -338,16 +338,23 @@ void TerrainTileManager::addCoordinateQuery(TerrainOfflineAirMapQuery* terrainQu qCDebug(TerrainQueryLog) << "TerrainTileManager::addCoordinateQuery count" << coordinates.count(); if (coordinates.length() > 0) { + bool error; QList altitudes; - if (!_getAltitudesForCoordinates(coordinates, altitudes)) { + if (!_getAltitudesForCoordinates(coordinates, altitudes, error)) { QueuedRequestInfo_t queuedRequestInfo = { terrainQueryInterface, QueryMode::QueryModeCoordinates, 0, 0, coordinates }; _requestQueue.append(queuedRequestInfo); return; } - qCDebug(TerrainQueryLog) << "All altitudes taken from cached data"; - terrainQueryInterface->_signalCoordinateHeights(coordinates.count() == altitudes.count(), altitudes); + if (error) { + QList noAltitudes; + qCWarning(TerrainQueryLog) << "addCoordinateQuery: signalling failure due to internal error"; + terrainQueryInterface->_signalCoordinateHeights(false, noAltitudes); + } else { + qCDebug(TerrainQueryLog) << "addCoordinateQuery: All altitudes taken from cached data"; + terrainQueryInterface->_signalCoordinateHeights(coordinates.count() == altitudes.count(), altitudes); + } } } @@ -370,19 +377,28 @@ void TerrainTileManager::addPathQuery(TerrainOfflineAirMapQuery* terrainQueryInt qCDebug(TerrainQueryLog) << "TerrainTileManager::addPathQuery start:end:coordCount" << startPoint << endPoint << coordinates.count(); + bool error; QList altitudes; - if (!_getAltitudesForCoordinates(coordinates, altitudes)) { + if (!_getAltitudesForCoordinates(coordinates, altitudes, error)) { QueuedRequestInfo_t queuedRequestInfo = { terrainQueryInterface, QueryMode::QueryModePath, latStep, lonStep, coordinates }; _requestQueue.append(queuedRequestInfo); return; } - qCDebug(TerrainQueryLog) << "All altitudes taken from cached data"; - terrainQueryInterface->_signalPathHeights(coordinates.count() == altitudes.count(), latStep, lonStep, altitudes); + if (error) { + QList noAltitudes; + qCWarning(TerrainQueryLog) << "addPathQuery: signalling failure due to internal error"; + terrainQueryInterface->_signalPathHeights(false, latStep, lonStep, noAltitudes); + } else { + qCDebug(TerrainQueryLog) << "addPathQuery: All altitudes taken from cached data"; + terrainQueryInterface->_signalPathHeights(coordinates.count() == altitudes.count(), latStep, lonStep, altitudes); + } } -bool TerrainTileManager::_getAltitudesForCoordinates(const QList& coordinates, QList& altitudes) +bool TerrainTileManager::_getAltitudesForCoordinates(const QList& coordinates, QList& altitudes, bool& error) { + error = false; + foreach (const QGeoCoordinate& coordinate, coordinates) { QString tileHash = _getTileHash(coordinate); _tilesMutex.lock(); @@ -406,14 +422,20 @@ bool TerrainTileManager::_getAltitudesForCoordinates(const QList return false; } else { if (_tiles[tileHash].isIn(coordinate)) { - altitudes.push_back(_tiles[tileHash].elevation(coordinate)); + double elevation = _tiles[tileHash].elevation(coordinate); + if (elevation < 0.0) { + error = true; + } + altitudes.push_back(elevation); } else { qCWarning(TerrainQueryLog) << "Error: coordinate not in tile region"; altitudes.push_back(-1.0); + error = true; } } _tilesMutex.unlock(); } + return true; } @@ -477,14 +499,29 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N // now try to query the data again for (int i = _requestQueue.count() - 1; i >= 0; i--) { + bool error; QList altitudes; QueuedRequestInfo_t& requestInfo = _requestQueue[i]; - if (_getAltitudesForCoordinates(requestInfo.coordinates, altitudes)) { + if (_getAltitudesForCoordinates(requestInfo.coordinates, altitudes, error)) { if (requestInfo.queryMode == QueryMode::QueryModeCoordinates) { - requestInfo.terrainQueryInterface->_signalCoordinateHeights(requestInfo.coordinates.count() == altitudes.count(), altitudes); + if (error) { + QList noAltitudes; + qCWarning(TerrainQueryLog) << "_terrainDone(coordinateQuery): signalling failure due to internal error"; + requestInfo.terrainQueryInterface->_signalCoordinateHeights(false, noAltitudes); + } else { + qCDebug(TerrainQueryLog) << "_terrainDone(coordinateQuery): All altitudes taken from cached data"; + requestInfo.terrainQueryInterface->_signalCoordinateHeights(requestInfo.coordinates.count() == altitudes.count(), altitudes); + } } else if (requestInfo.queryMode == QueryMode::QueryModePath) { - requestInfo.terrainQueryInterface->_signalPathHeights(requestInfo.coordinates.count() == altitudes.count(), requestInfo.latStep, requestInfo.lonStep, altitudes); + if (error) { + QList noAltitudes; + qCWarning(TerrainQueryLog) << "_terrainDone(coordinateQuery): signalling failure due to internal error"; + requestInfo.terrainQueryInterface->_signalPathHeights(false, requestInfo.latStep, requestInfo.lonStep, noAltitudes); + } else { + qCDebug(TerrainQueryLog) << "_terrainDone(coordinateQuery): All altitudes taken from cached data"; + requestInfo.terrainQueryInterface->_signalPathHeights(requestInfo.coordinates.count() == altitudes.count(), requestInfo.latStep, requestInfo.lonStep, altitudes); + } } _requestQueue.removeAt(i); } diff --git a/src/Terrain/TerrainQuery.h b/src/Terrain/TerrainQuery.h index b913d06..1073fae 100644 --- a/src/Terrain/TerrainQuery.h +++ b/src/Terrain/TerrainQuery.h @@ -140,9 +140,9 @@ private: QList coordinates; } QueuedRequestInfo_t; - void _tileFailed(void); - bool _getAltitudesForCoordinates(const QList& coordinates, QList& altitudes); - QString _getTileHash(const QGeoCoordinate& coordinate); /// Method to create a unique string for each tile + void _tileFailed (void); + bool _getAltitudesForCoordinates (const QList& coordinates, QList& altitudes, bool& error); + QString _getTileHash (const QGeoCoordinate& coordinate); QList _requestQueue; State _state = State::Idle;