Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
4eedf9d5
Commit
4eedf9d5
authored
Apr 16, 2018
by
Gus Grubba
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Separate terrain from tile maps within cached tile request system.
parent
d7a73b51
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
62 additions
and
48 deletions
+62
-48
QGeoMapReplyQGC.cpp
src/QtLocationPlugin/QGeoMapReplyQGC.cpp
+42
-23
QGeoMapReplyQGC.h
src/QtLocationPlugin/QGeoMapReplyQGC.h
+3
-0
TerrainQuery.cc
src/Terrain/TerrainQuery.cc
+6
-14
TerrainQuery.h
src/Terrain/TerrainQuery.h
+11
-11
No files found.
src/QtLocationPlugin/QGeoMapReplyQGC.cpp
View file @
4eedf9d5
...
...
@@ -123,23 +123,23 @@ QGeoTiledMapReplyQGC::networkReplyFinished()
}
QByteArray
a
=
_reply
->
readAll
();
QString
format
=
getQGCMapEngine
()
->
urlFactory
()
->
getImageFormat
((
UrlFactory
::
MapType
)
tileSpec
().
mapId
(),
a
);
// convert "a" to binary in case we have elevation data
//-- Test for a specialized, elevation data (not map tile)
if
((
UrlFactory
::
MapType
)
tileSpec
().
mapId
()
==
UrlFactory
::
MapType
::
AirmapElevation
)
{
a
=
TerrainTile
::
serialize
(
a
);
if
(
a
.
isEmpty
())
{
emit
aborted
();
return
;
//-- Cache it if valid
if
(
!
a
.
isEmpty
())
{
getQGCMapEngine
()
->
cacheTile
(
UrlFactory
::
MapType
::
AirmapElevation
,
tileSpec
().
x
(),
tileSpec
().
y
(),
tileSpec
().
zoom
(),
a
,
format
)
;
}
}
setMapImageData
(
a
);
if
(
!
format
.
isEmpty
())
{
setMapImageFormat
(
format
);
getQGCMapEngine
()
->
cacheTile
((
UrlFactory
::
MapType
)
tileSpec
().
mapId
(),
tileSpec
().
x
(),
tileSpec
().
y
(),
tileSpec
().
zoom
(),
a
,
format
);
emit
terrainDone
(
a
,
QNetworkReply
::
NoError
);
}
else
{
//-- This is a map tile. Process and ache it if valid.
setMapImageData
(
a
);
if
(
!
format
.
isEmpty
())
{
setMapImageFormat
(
format
);
getQGCMapEngine
()
->
cacheTile
((
UrlFactory
::
MapType
)
tileSpec
().
mapId
(),
tileSpec
().
x
(),
tileSpec
().
y
(),
tileSpec
().
zoom
(),
a
,
format
);
}
setFinished
(
true
);
}
setFinished
(
true
);
_clearReply
();
}
...
...
@@ -151,11 +151,17 @@ QGeoTiledMapReplyQGC::networkReplyError(QNetworkReply::NetworkError error)
if
(
!
_reply
)
{
return
;
}
if
(
error
!=
QNetworkReply
::
OperationCanceledError
)
{
qWarning
()
<<
"Fetch tile error:"
<<
_reply
->
errorString
();
setError
(
QGeoTiledMapReply
::
CommunicationError
,
_reply
->
errorString
());
//-- Test for a specialized, elevation data (not map tile)
if
((
UrlFactory
::
MapType
)
tileSpec
().
mapId
()
==
UrlFactory
::
MapType
::
AirmapElevation
)
{
emit
terrainDone
(
QByteArray
(),
error
);
}
else
{
//-- Regular map tile
if
(
error
!=
QNetworkReply
::
OperationCanceledError
)
{
qWarning
()
<<
"Fetch tile error:"
<<
_reply
->
errorString
();
setError
(
QGeoTiledMapReply
::
CommunicationError
,
_reply
->
errorString
());
}
setFinished
(
true
);
}
setFinished
(
true
);
_clearReply
();
}
...
...
@@ -164,8 +170,12 @@ void
QGeoTiledMapReplyQGC
::
cacheError
(
QGCMapTask
::
TaskType
type
,
QString
/*errorString*/
)
{
if
(
!
getQGCMapEngine
()
->
isInternetActive
())
{
setError
(
QGeoTiledMapReply
::
CommunicationError
,
"Network not available"
);
setFinished
(
true
);
if
((
UrlFactory
::
MapType
)
tileSpec
().
mapId
()
==
UrlFactory
::
MapType
::
AirmapElevation
)
{
emit
terrainDone
(
QByteArray
(),
QNetworkReply
::
NetworkSessionFailedError
);
}
else
{
setError
(
QGeoTiledMapReply
::
CommunicationError
,
"Network not available"
);
setFinished
(
true
);
}
}
else
{
if
(
type
!=
QGCMapTask
::
taskFetchTile
)
{
qWarning
()
<<
"QGeoTiledMapReplyQGC::cacheError() for wrong task"
;
...
...
@@ -196,10 +206,16 @@ QGeoTiledMapReplyQGC::cacheError(QGCMapTask::TaskType type, QString /*errorStrin
void
QGeoTiledMapReplyQGC
::
cacheReply
(
QGCCacheTile
*
tile
)
{
setMapImageData
(
tile
->
img
());
setMapImageFormat
(
tile
->
format
());
setFinished
(
true
);
setCached
(
true
);
//-- Test for a specialized, elevation data (not map tile)
if
((
UrlFactory
::
MapType
)
tileSpec
().
mapId
()
==
UrlFactory
::
MapType
::
AirmapElevation
)
{
emit
terrainDone
(
tile
->
img
(),
QNetworkReply
::
NoError
);
}
else
{
//-- Regular map tile
setMapImageData
(
tile
->
img
());
setMapImageFormat
(
tile
->
format
());
setFinished
(
true
);
setCached
(
true
);
}
tile
->
deleteLater
();
}
...
...
@@ -210,5 +226,8 @@ QGeoTiledMapReplyQGC::timeout()
if
(
_reply
)
{
_reply
->
abort
();
}
if
((
UrlFactory
::
MapType
)
tileSpec
().
mapId
()
==
UrlFactory
::
MapType
::
AirmapElevation
)
{
emit
terrainDone
(
QByteArray
(),
QNetworkReply
::
TimeoutError
);
}
emit
aborted
();
}
src/QtLocationPlugin/QGeoMapReplyQGC.h
View file @
4eedf9d5
...
...
@@ -61,6 +61,9 @@ public:
~
QGeoTiledMapReplyQGC
();
void
abort
();
signals:
void
terrainDone
(
QByteArray
responseBytes
,
QNetworkReply
::
NetworkError
error
);
private
slots
:
void
networkReplyFinished
();
void
networkReplyError
(
QNetworkReply
::
NetworkError
error
);
...
...
src/Terrain/TerrainQuery.cc
View file @
4eedf9d5
...
...
@@ -374,8 +374,7 @@ bool TerrainTileManager::_getAltitudesForCoordinates(const QList<QGeoCoordinate>
spec
.
setZoom
(
1
);
spec
.
setMapId
(
UrlFactory
::
AirmapElevation
);
QGeoTiledMapReplyQGC
*
reply
=
new
QGeoTiledMapReplyQGC
(
&
_networkManager
,
request
,
spec
);
connect
(
reply
,
&
QGeoTiledMapReplyQGC
::
finished
,
this
,
&
TerrainTileManager
::
_fetchedTile
);
connect
(
reply
,
&
QGeoTiledMapReplyQGC
::
aborted
,
this
,
&
TerrainTileManager
::
_fetchedTile
);
connect
(
reply
,
&
QGeoTiledMapReplyQGC
::
terrainDone
,
this
,
&
TerrainTileManager
::
_terrainDone
);
_state
=
State
::
Downloading
;
}
_tilesMutex
.
unlock
();
...
...
@@ -406,7 +405,7 @@ void TerrainTileManager::_tileFailed(void)
_requestQueue
.
clear
();
}
void
TerrainTileManager
::
_
fetchedTile
(
)
void
TerrainTileManager
::
_
terrainDone
(
QByteArray
responseBytes
,
QNetworkReply
::
NetworkError
error
)
{
QGeoTiledMapReplyQGC
*
reply
=
qobject_cast
<
QGeoTiledMapReplyQGC
*>
(
QObject
::
sender
());
_state
=
State
::
Idle
;
...
...
@@ -421,26 +420,19 @@ void TerrainTileManager::_fetchedTile()
QString
hash
=
QGCMapEngine
::
getTileHash
(
UrlFactory
::
AirmapElevation
,
spec
.
x
(),
spec
.
y
(),
spec
.
zoom
());
// handle potential errors
if
(
reply
->
error
()
!=
QGeoTiledMapReply
::
NoError
)
{
if
(
reply
->
error
()
==
QGeoTiledMapReply
::
CommunicationError
)
{
qCDebug
(
TerrainQueryLog
)
<<
"Elevation tile fetching returned communication error. "
<<
reply
->
errorString
();
}
else
{
qCDebug
(
TerrainQueryLog
)
<<
"Elevation tile fetching returned error. "
<<
reply
->
errorString
();
}
if
(
error
!=
QNetworkReply
::
NoError
)
{
qCDebug
(
TerrainQueryLog
)
<<
"Elevation tile fetching returned error ("
<<
error
<<
")"
;
_tileFailed
();
reply
->
deleteLater
();
return
;
}
if
(
!
reply
->
isFinished
())
{
qCDebug
(
TerrainQueryLog
)
<<
"Error in fetching elevation tile.
Not finished. "
<<
reply
->
errorString
()
;
if
(
responseBytes
.
isEmpty
())
{
qCDebug
(
TerrainQueryLog
)
<<
"Error in fetching elevation tile.
Empty response."
;
_tileFailed
();
reply
->
deleteLater
();
return
;
}
// parse received data and insert into hash table
QByteArray
responseBytes
=
reply
->
mapImageData
();
qWarning
()
<<
"Received some bytes of terrain data: "
<<
responseBytes
.
size
();
TerrainTile
*
terrainTile
=
new
TerrainTile
(
responseBytes
);
...
...
src/Terrain/TerrainQuery.h
View file @
4eedf9d5
...
...
@@ -62,20 +62,20 @@ public:
TerrainAirMapQuery
(
QObject
*
parent
=
NULL
);
// Overrides from TerrainQueryInterface
void
requestCoordinateHeights
(
const
QList
<
QGeoCoordinate
>&
coordinates
)
final
;
void
requestPathHeights
(
const
QGeoCoordinate
&
fromCoord
,
const
QGeoCoordinate
&
toCoord
)
final
;
void
requestCarpetHeights
(
const
QGeoCoordinate
&
swCoord
,
const
QGeoCoordinate
&
neCoord
,
bool
statsOnly
)
final
;
void
requestCoordinateHeights
(
const
QList
<
QGeoCoordinate
>&
coordinates
)
final
;
void
requestPathHeights
(
const
QGeoCoordinate
&
fromCoord
,
const
QGeoCoordinate
&
toCoord
)
final
;
void
requestCarpetHeights
(
const
QGeoCoordinate
&
swCoord
,
const
QGeoCoordinate
&
neCoord
,
bool
statsOnly
)
final
;
private
slots
:
void
_requestError
(
QNetworkReply
::
NetworkError
code
);
void
_requestFinished
(
void
);
void
_requestError
(
QNetworkReply
::
NetworkError
code
);
void
_requestFinished
(
);
private:
void
_sendQuery
(
const
QString
&
path
,
const
QUrlQuery
&
urlQuery
);
void
_requestFailed
(
void
);
void
_parseCoordinateData
(
const
QJsonValue
&
coordinateJson
);
void
_parsePathData
(
const
QJsonValue
&
pathJson
);
void
_parseCarpetData
(
const
QJsonValue
&
carpetJson
);
void
_sendQuery
(
const
QString
&
path
,
const
QUrlQuery
&
urlQuery
);
void
_requestFailed
(
void
);
void
_parseCoordinateData
(
const
QJsonValue
&
coordinateJson
);
void
_parsePathData
(
const
QJsonValue
&
pathJson
);
void
_parseCarpetData
(
const
QJsonValue
&
carpetJson
);
enum
QueryMode
{
QueryModeCoordinates
,
...
...
@@ -117,7 +117,7 @@ public:
void
addPathQuery
(
TerrainOfflineAirMapQuery
*
terrainQueryInterface
,
const
QGeoCoordinate
&
startPoint
,
const
QGeoCoordinate
&
endPoint
);
private
slots
:
void
_
fetchedTile
(
void
);
/// slot to handle fetched elevation tiles
void
_
terrainDone
(
QByteArray
responseBytes
,
QNetworkReply
::
NetworkError
error
);
private:
enum
class
State
{
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment