QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
TerrainTileManager.cc
Go to the documentation of this file.
2#include "TerrainTile.h"
5#include "QGeoMapReplyQGC.h"
6#include "QGCMapUrlEngine.h"
8#include "SettingsManager.h"
9#include "FlightMapSettings.h"
10#include "QGCLoggingCategory.h"
11#include "QGCGeo.h"
12
13#include <QtLocation/private/qgeotilespec_p.h>
14#include <QtNetwork/QNetworkAccessManager>
15#include <QtNetwork/QNetworkRequest>
16
17#include <limits>
18
19#include "QGCNetworkHelper.h"
20
21QGC_LOGGING_CATEGORY(TerrainTileManagerLog, "Terrain.TerrainTileManager")
22
23namespace {
24 constexpr int kMaxCarpetGridSize = 10000;
25}
26
27Q_GLOBAL_STATIC(TerrainTileManager, _terrainTileManager)
28
30{
31 return _terrainTileManager();
32}
33
35 : QObject(parent)
36 , _networkManager(new QNetworkAccessManager(this))
37{
38 qCDebug(TerrainTileManagerLog) << this;
39
40 QGCNetworkHelper::configureProxy(_networkManager);
41}
42
44{
45 qDeleteAll(_tiles);
46
47 qCDebug(TerrainTileManagerLog) << this;
48}
49
50bool TerrainTileManager::getAltitudesForCoordinates(const QList<QGeoCoordinate> &coordinates, QList<double> &altitudes, bool &error)
51{
52 error = false;
53
54 const QString elevationProviderName = SettingsManager::instance()->flightMapSettings()->elevationMapProvider()->rawValue().toString();
55 const SharedMapProvider provider = UrlFactory::getMapProviderFromProviderType(elevationProviderName);
56 for (const QGeoCoordinate &coordinate: coordinates) {
57 const QString tileHash = UrlFactory::getTileHash(
58 provider->getMapName(),
59 provider->long2tileX(coordinate.longitude(), 1),
60 provider->lat2tileY(coordinate.latitude(), 1),
61 1
62 );
63 qCDebug(TerrainTileManagerLog) << "hash:coordinate" << tileHash << coordinate;
64
65 TerrainTile* const tile = _getCachedTile(tileHash);
66 if (tile) {
67 const double elevation = tile->elevation(coordinate);
68 if (qIsNaN(elevation)) {
69 error = true;
70 qCWarning(TerrainTileManagerLog) << "Internal Error: missing elevation in tile cache";
71 } else {
72 qCDebug(TerrainTileManagerLog) << "returning elevation from tile cache" << elevation;
73 }
74 altitudes.push_back(elevation);
75 } else if (_state != TerrainQuery::State::Downloading) {
76 QGeoTileSpec spec;
77 spec.setX(provider->long2tileX(coordinate.longitude(), 1));
78 spec.setY(provider->lat2tileY(coordinate.latitude(), 1));
79 spec.setZoom(1);
80 spec.setMapId(provider->getMapId());
81 const QNetworkRequest request = QGeoTileFetcherQGC::getNetworkRequest(spec.mapId(), spec.x(), spec.y(), spec.zoom());
82 QGeoTiledMapReplyQGC *reply = new QGeoTiledMapReplyQGC(_networkManager, request, spec, this);
83 (void) connect(reply, &QGeoTiledMapReplyQGC::finished, this, &TerrainTileManager::_terrainDone);
84 if (reply->init()) {
86 } else {
87 reply->deleteLater();
88 }
89 return false;
90 } else {
91 return false;
92 }
93 }
94
95 return true;
96}
97
98void TerrainTileManager::addCoordinateQuery(TerrainQueryInterface *terrainQueryInterface, const QList<QGeoCoordinate> &coordinates)
99{
100 qCDebug(TerrainTileManagerLog) << "count" << coordinates.count();
101
102 if (coordinates.isEmpty()) {
103 return;
104 }
105
106 bool error;
107 QList<double> altitudes;
108 if (!getAltitudesForCoordinates(coordinates, altitudes, error)) {
109 qCDebug(TerrainTileManagerLog) << "queue count" << _requestQueue.count();
110 const QueuedRequestInfo_t queuedRequestInfo = {
111 terrainQueryInterface,
113 0,
114 0,
115 coordinates,
116 false,
117 0,
118 0
119 };
120 _requestQueue.enqueue(queuedRequestInfo);
121 return;
122 }
123
124 if (error) {
125 QList<double> noAltitudes;
126 qCWarning(TerrainTileManagerLog) << "signalling failure due to internal error";
127 terrainQueryInterface->signalCoordinateHeights(false, noAltitudes);
128 return;
129 }
130
131 qCDebug(TerrainTileManagerLog) << "all altitudes taken from cached data";
132 terrainQueryInterface->signalCoordinateHeights((coordinates.count() == altitudes.count()), altitudes);
133}
134
135void TerrainTileManager::addPathQuery(TerrainQueryInterface *terrainQueryInterface, const QGeoCoordinate &startPoint, const QGeoCoordinate &endPoint)
136{
137 double distanceBetween;
138 double finalDistanceBetween;
139 const QList<QGeoCoordinate> coordinates = _pathQueryToCoords(startPoint, endPoint, distanceBetween, finalDistanceBetween);
140
141 bool error;
142 QList<double> altitudes;
143 if (!getAltitudesForCoordinates(coordinates, altitudes, error)) {
144 qCDebug(TerrainTileManagerLog) << "queue count" << _requestQueue.count();
145 const QueuedRequestInfo_t queuedRequestInfo = {
146 terrainQueryInterface,
148 distanceBetween,
149 finalDistanceBetween,
150 coordinates,
151 false,
152 0,
153 0
154 };
155 _requestQueue.enqueue(queuedRequestInfo);
156 return;
157 }
158
159 if (error) {
160 QList<double> noAltitudes;
161 qCWarning(TerrainTileManagerLog) << "signalling failure due to internal error";
162 terrainQueryInterface->signalPathHeights(false, distanceBetween, finalDistanceBetween, noAltitudes);
163 return;
164 }
165
166 qCDebug(TerrainTileManagerLog) << "all altitudes taken from cached data";
167 terrainQueryInterface->signalPathHeights((coordinates.count() == altitudes.count()), distanceBetween, finalDistanceBetween, altitudes);
168}
169
170void TerrainTileManager::addCarpetQuery(TerrainQueryInterface *terrainQueryInterface, const QGeoCoordinate &swCoord, const QGeoCoordinate &neCoord, bool statsOnly)
171{
172 if (swCoord.longitude() > neCoord.longitude() || swCoord.latitude() > neCoord.latitude()) {
173 qCWarning(TerrainTileManagerLog) << "Invalid carpet bounds: SW must be south-west of NE";
174 terrainQueryInterface->signalCarpetHeights(false, qQNaN(), qQNaN(), QList<QList<double>>());
175 return;
176 }
177
178 const int gridSizeLat = qCeil((neCoord.latitude() - swCoord.latitude()) / TerrainTileCopernicus::kTileValueSpacingDegrees);
179 const int gridSizeLon = qCeil((neCoord.longitude() - swCoord.longitude()) / TerrainTileCopernicus::kTileValueSpacingDegrees);
180
181 if (gridSizeLat <= 0 || gridSizeLon <= 0) {
182 qCWarning(TerrainTileManagerLog) << "Carpet area too small";
183 terrainQueryInterface->signalCarpetHeights(false, qQNaN(), qQNaN(), QList<QList<double>>());
184 return;
185 }
186
187 if (gridSizeLat > kMaxCarpetGridSize || gridSizeLon > kMaxCarpetGridSize) {
188 qCWarning(TerrainTileManagerLog) << "Carpet area too large"
189 << "gridSizeLat:" << gridSizeLat
190 << "gridSizeLon:" << gridSizeLon
191 << "maxGridSize:" << kMaxCarpetGridSize;
192 terrainQueryInterface->signalCarpetHeights(false, qQNaN(), qQNaN(), QList<QList<double>>());
193 return;
194 }
195
196 QList<QGeoCoordinate> coordinates;
197 for (int latIdx = 0; latIdx <= gridSizeLat; latIdx++) {
198 const double lat = swCoord.latitude() + (latIdx * TerrainTileCopernicus::kTileValueSpacingDegrees);
199 for (int lonIdx = 0; lonIdx <= gridSizeLon; lonIdx++) {
200 const double lon = swCoord.longitude() + (lonIdx * TerrainTileCopernicus::kTileValueSpacingDegrees);
201 (void) coordinates.append(QGeoCoordinate(lat, lon));
202 }
203 }
204
205 bool error;
206 QList<double> altitudes;
207 if (!getAltitudesForCoordinates(coordinates, altitudes, error)) {
208 qCDebug(TerrainTileManagerLog) << "carpet query queued, count" << _requestQueue.count();
209 const QueuedRequestInfo_t queuedRequestInfo = {
210 terrainQueryInterface,
212 0,
213 0,
214 coordinates,
215 statsOnly,
216 gridSizeLat + 1,
217 gridSizeLon + 1
218 };
219 _requestQueue.enqueue(queuedRequestInfo);
220 return;
221 }
222
223 if (error) {
224 qCWarning(TerrainTileManagerLog) << "signalling carpet failure due to internal error";
225 terrainQueryInterface->signalCarpetHeights(false, qQNaN(), qQNaN(), QList<QList<double>>());
226 return;
227 }
228
229 double minHeight, maxHeight;
230 QList<QList<double>> carpet;
231 _processCarpetResults(altitudes, gridSizeLat + 1, gridSizeLon + 1, statsOnly, minHeight, maxHeight, carpet);
232
233 qCDebug(TerrainTileManagerLog) << "carpet altitudes from cached data, min:" << minHeight << "max:" << maxHeight;
234 terrainQueryInterface->signalCarpetHeights(true, minHeight, maxHeight, carpet);
235}
236
237QList<QGeoCoordinate> TerrainTileManager::_pathQueryToCoords(const QGeoCoordinate &fromCoord, const QGeoCoordinate &toCoord, double &distanceBetween, double &finalDistanceBetween)
238{
239 const double totalDistance = QGCGeo::geodesicDistance(fromCoord, toCoord);
240 // TODO: get spacing from terrainQueryInterface
241 const int numPoints = qMax(2, qCeil(totalDistance / TerrainTileCopernicus::kTileValueSpacingMeters) + 1);
242
243 QList<QGeoCoordinate> coordinates = QGCGeo::interpolatePath(fromCoord, toCoord, numPoints);
244
245 if (coordinates.size() >= 2) {
246 distanceBetween = QGCGeo::geodesicDistance(coordinates[0], coordinates[1]);
247 finalDistanceBetween = QGCGeo::geodesicDistance(coordinates[coordinates.size() - 2], coordinates.last());
248 } else {
249 distanceBetween = finalDistanceBetween = totalDistance;
250 }
251
252 qCDebug(TerrainTileManagerLog) << "fromCoord:toCoord:distanceBetween:finalDistanceBetween:coordCount"
253 << fromCoord << toCoord << distanceBetween << finalDistanceBetween << coordinates.count();
254
255 return coordinates;
256}
257
258void TerrainTileManager::_tileFailed()
259{
260 QList<double> noAltitudes;
261
262 for (const QueuedRequestInfo_t &requestInfo: _requestQueue) {
263 if (requestInfo.terrainQueryInterface.isNull()) {
264 continue;
265 }
266 switch (requestInfo.queryMode) {
268 requestInfo.terrainQueryInterface->signalCoordinateHeights(false, noAltitudes);
269 break;
271 requestInfo.terrainQueryInterface->signalPathHeights(false, requestInfo.distanceBetween, requestInfo.finalDistanceBetween, noAltitudes);
272 break;
274 requestInfo.terrainQueryInterface->signalCarpetHeights(false, qQNaN(), qQNaN(), QList<QList<double>>());
275 break;
276 default:
277 continue;
278 }
279 }
280
281 _requestQueue.clear();
282}
283
284void TerrainTileManager::_terrainDone()
285{
287
288 QGeoTiledMapReplyQGC* const reply = qobject_cast<QGeoTiledMapReplyQGC*>(QObject::sender());
289 if (!reply) {
290 qCWarning(TerrainTileManagerLog) << "Elevation tile fetched but invalid reply data type.";
291 return;
292 }
293 reply->deleteLater();
294
295 const QByteArray responseBytes = reply->mapImageData();
296 const QGeoTileSpec spec = reply->tileSpec();
297
298 if (reply->error() != QGeoTiledMapReplyQGC::NoError) {
299 qCWarning(TerrainTileManagerLog) << "Elevation tile fetching returned error:" << reply->errorString();
300 _tileFailed();
301 return;
302 }
303
304 if (responseBytes.isEmpty()) {
305 qCWarning(TerrainTileManagerLog) << "Error in fetching elevation tile. Empty response.";
306 _tileFailed();
307 return;
308 }
309
310 qCDebug(TerrainTileManagerLog) << "Received some bytes of terrain data:" << responseBytes.size();
311
312 const QString hash = UrlFactory::getTileHash(UrlFactory::getProviderTypeFromQtMapId(spec.mapId()), spec.x(), spec.y(), spec.zoom());
313 _cacheTile(responseBytes, hash);
314
315 for (qsizetype i = _requestQueue.count() - 1; i >= 0; i--) {
316 bool error;
317 QList<double> altitudes;
318 QueuedRequestInfo_t &requestInfo = _requestQueue[i];
319
320 if (requestInfo.terrainQueryInterface.isNull()) {
321 _requestQueue.removeAt(i);
322 continue;
323 }
324
325 if (!getAltitudesForCoordinates(requestInfo.coordinates, altitudes, error)) {
326 continue;
327 }
328
329 switch (requestInfo.queryMode) {
331 if (error) {
332 qCWarning(TerrainTileManagerLog) << "signalling failure due to internal error";
333 QList<double> noAltitudes;
334 requestInfo.terrainQueryInterface->signalCoordinateHeights(false, noAltitudes);
335 } else {
336 qCDebug(TerrainTileManagerLog) << "All altitudes taken from cached data";
337 requestInfo.terrainQueryInterface->signalCoordinateHeights(requestInfo.coordinates.count() == altitudes.count(), altitudes);
338 }
339 break;
341 if (error) {
342 qCWarning(TerrainTileManagerLog) << "signalling failure due to internal error";
343 QList<double> noAltitudes;
344 requestInfo.terrainQueryInterface->signalPathHeights(false, requestInfo.distanceBetween, requestInfo.finalDistanceBetween, noAltitudes);
345 } else {
346 qCDebug(TerrainTileManagerLog) << "All altitudes taken from cached data";
347 requestInfo.terrainQueryInterface->signalPathHeights(requestInfo.coordinates.count() == altitudes.count(), requestInfo.distanceBetween, requestInfo.finalDistanceBetween, altitudes);
348 }
349 break;
351 if (error) {
352 qCWarning(TerrainTileManagerLog) << "signalling carpet failure due to internal error";
353 requestInfo.terrainQueryInterface->signalCarpetHeights(false, qQNaN(), qQNaN(), QList<QList<double>>());
354 } else {
355 double minHeight, maxHeight;
356 QList<QList<double>> carpet;
357 _processCarpetResults(altitudes, requestInfo.carpetGridSizeLat, requestInfo.carpetGridSizeLon,
358 requestInfo.carpetStatsOnly, minHeight, maxHeight, carpet);
359
360 qCDebug(TerrainTileManagerLog) << "carpet altitudes from cached data, min:" << minHeight << "max:" << maxHeight;
361 requestInfo.terrainQueryInterface->signalCarpetHeights(true, minHeight, maxHeight, carpet);
362 }
363 break;
364 default:
365 break;
366 }
367
368 _requestQueue.removeAt(i);
369 }
370}
371
372void TerrainTileManager::_cacheTile(const QByteArray &data, const QString &hash)
373{
374 TerrainTile* const terrainTile = new TerrainTile(data);
375 if (!terrainTile->isValid()) {
376 delete terrainTile;
377 qCWarning(TerrainTileManagerLog) << "Received invalid tile";
378 return;
379 }
380
381 QMutexLocker locker(&_tilesMutex);
382 if (!_tiles.contains(hash)) {
383 (void) _tiles.insert(hash, terrainTile);
384 } else {
385 delete terrainTile;
386 }
387}
388
389TerrainTile *TerrainTileManager::_getCachedTile(const QString &hash)
390{
391 QMutexLocker locker(&_tilesMutex);
392
393 if (!_tiles.contains(hash)) {
394 return nullptr;
395 }
396
397 TerrainTile* const tile = _tiles[hash];
398 if (!tile->isValid()) {
399 return nullptr;
400 }
401
402 return tile;
403}
404
405void TerrainTileManager::_processCarpetResults(const QList<double> &altitudes, int gridSizeLat, int gridSizeLon,
406 bool statsOnly, double &minHeight, double &maxHeight, QList<QList<double>> &carpet)
407{
408 minHeight = std::numeric_limits<double>::max();
409 maxHeight = std::numeric_limits<double>::lowest();
410
411 int idx = 0;
412 for (int latIdx = 0; latIdx < gridSizeLat; latIdx++) {
413 QList<double> row;
414 for (int lonIdx = 0; lonIdx < gridSizeLon; lonIdx++) {
415 const double height = altitudes[idx++];
416 minHeight = qMin(minHeight, height);
417 maxHeight = qMax(maxHeight, height);
418 if (!statsOnly) {
419 (void) row.append(height);
420 }
421 }
422 if (!statsOnly) {
423 (void) carpet.append(row);
424 }
425 }
426}
Q_GLOBAL_STATIC(FirmwarePluginFactoryRegister, _firmwarePluginFactoryRegisterInstance)
Error error
Geographic coordinate conversion utilities using GeographicLib.
#define QGC_LOGGING_CATEGORY(name, categoryStr)
std::shared_ptr< const MapProvider > SharedMapProvider
Fact *elevationMapProvider READ elevationMapProvider CONSTANT Fact * elevationMapProvider()
static QNetworkRequest getNetworkRequest(int mapId, int x, int y, int zoom)
Base class for offline/online terrain queries.
void signalPathHeights(bool success, double distanceBetween, double finalDistanceBetween, const QList< double > &heights)
void signalCoordinateHeights(bool success, const QList< double > &heights)
void signalCarpetHeights(bool success, double minHeight, double maxHeight, const QList< QList< double > > &carpet)
static constexpr double kTileValueSpacingDegrees
1 Arc-Second spacing of elevation values
static constexpr double kTileValueSpacingMeters
bool getAltitudesForCoordinates(const QList< QGeoCoordinate > &coordinates, QList< double > &altitudes, bool &error)
TerrainTileManager(QObject *parent=nullptr)
void addPathQuery(TerrainQueryInterface *terrainQueryInterface, const QGeoCoordinate &startPoint, const QGeoCoordinate &endPoint)
void addCarpetQuery(TerrainQueryInterface *terrainQueryInterface, const QGeoCoordinate &swCoord, const QGeoCoordinate &neCoord, bool statsOnly)
void addCoordinateQuery(TerrainQueryInterface *terrainQueryInterface, const QList< QGeoCoordinate > &coordinates)
double elevation(const QGeoCoordinate &coordinate) const
bool isValid() const
Definition TerrainTile.h:23
static QString getTileHash(QStringView type, int x, int y, int z)
static QString getProviderTypeFromQtMapId(int qtMapId)
static std::shared_ptr< const MapProvider > getMapProviderFromProviderType(QStringView type)
QList< QGeoCoordinate > interpolatePath(const QGeoCoordinate &from, const QGeoCoordinate &to, int numPoints)
Definition QGCGeo.cc:308
double geodesicDistance(const QGeoCoordinate &from, const QGeoCoordinate &to)
Definition QGCGeo.cc:229
void configureProxy(QNetworkAccessManager *manager)
Set up default proxy configuration on a network manager.