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
5ba79984
Commit
5ba79984
authored
Sep 18, 2019
by
Pierre TILAK
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Airmap Elevation working again
parent
46d61652
Changes
9
Hide whitespace changes
Inline
Side-by-side
Showing
9 changed files
with
44 additions
and
38 deletions
+44
-38
ElevationMapProvider.cpp
src/QtLocationPlugin/ElevationMapProvider.cpp
+2
-3
ElevationMapProvider.h
src/QtLocationPlugin/ElevationMapProvider.h
+4
-2
MapProvider.h
src/QtLocationPlugin/MapProvider.h
+2
-2
QGCMapEngine.cpp
src/QtLocationPlugin/QGCMapEngine.cpp
+24
-15
QGCMapUrlEngine.cpp
src/QtLocationPlugin/QGCMapUrlEngine.cpp
+2
-10
QGCMapUrlEngine.h
src/QtLocationPlugin/QGCMapUrlEngine.h
+1
-0
OfflineMap.qml
src/QtLocationPlugin/QMLControl/OfflineMap.qml
+1
-1
QGCMapEngineManager.cc
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc
+0
-1
TerrainQuery.cc
src/Terrain/TerrainQuery.cc
+8
-4
No files found.
src/QtLocationPlugin/ElevationMapProvider.cpp
View file @
5ba79984
...
...
@@ -10,17 +10,16 @@ ElevationProvider::ElevationProvider(QString imageFormat, quint32 averageSize,
QObject
*
parent
)
:
MapProvider
(
QString
(
"https://api.airmap.com/"
),
imageFormat
,
averageSize
,
mapType
,
parent
)
{}
ElevationProvider
::~
ElevationProvider
()
{}
//-----------------------------------------------------------------------------
int
ElevationProvider
::
long2tileX
(
double
lon
,
int
z
)
{
int
Airmap
ElevationProvider
::
long2tileX
(
double
lon
,
int
z
)
{
Q_UNUSED
(
z
);
return
static_cast
<
int
>
(
floor
((
lon
+
180.0
)
/
srtm1TileSize
));
}
//-----------------------------------------------------------------------------
int
ElevationProvider
::
lat2tileY
(
double
lat
,
int
z
)
{
int
Airmap
ElevationProvider
::
lat2tileY
(
double
lat
,
int
z
)
{
Q_UNUSED
(
z
);
return
static_cast
<
int
>
(
floor
((
lat
+
90.0
)
/
srtm1TileSize
));
}
...
...
src/QtLocationPlugin/ElevationMapProvider.h
View file @
5ba79984
...
...
@@ -21,8 +21,6 @@ class ElevationProvider : public MapProvider {
~
ElevationProvider
();
int
long2tileX
(
double
lon
,
int
z
);
int
lat2tileY
(
double
lat
,
int
z
);
protected:
// Define the url to Request
...
...
@@ -40,6 +38,10 @@ class AirmapElevationProvider : public ElevationProvider {
:
ElevationProvider
(
QString
(
"bin"
),
AVERAGE_AIRMAP_ELEV_SIZE
,
QGeoMapType
::
StreetMap
,
parent
)
{}
int
long2tileX
(
double
lon
,
int
z
);
int
lat2tileY
(
double
lat
,
int
z
);
protected:
QString
_getURL
(
int
x
,
int
y
,
int
zoom
,
QNetworkAccessManager
*
networkManager
);
...
...
src/QtLocationPlugin/MapProvider.h
View file @
5ba79984
...
...
@@ -29,9 +29,9 @@ class MapProvider : public QObject {
QGeoMapType
::
MapStyle
getMapStyle
(){
return
_mapType
;}
int
long2tileX
(
double
lon
,
int
z
);
virtual
int
long2tileX
(
double
lon
,
int
z
);
int
lat2tileY
(
double
lat
,
int
z
);
virtual
int
lat2tileY
(
double
lat
,
int
z
);
protected:
QString
_tileXYToQuadKey
(
int
tileX
,
int
tileY
,
int
levelOfDetail
);
...
...
src/QtLocationPlugin/QGCMapEngine.cpp
View file @
5ba79984
...
...
@@ -236,28 +236,37 @@ QGCMapEngine::hashToType(const QString& hash)
}
//-----------------------------------------------------------------------------
QGCFetchTileTask
*
QGCFetchTileTask
*
QGCMapEngine
::
createFetchTileTask
(
QString
type
,
int
x
,
int
y
,
int
z
)
{
QString
hash
=
getTileHash
(
type
,
x
,
y
,
z
);
QGCFetchTileTask
*
task
=
new
QGCFetchTileTask
(
hash
);
return
task
;
QString
hash
=
getTileHash
(
type
,
x
,
y
,
z
);
QGCFetchTileTask
*
task
=
new
QGCFetchTileTask
(
hash
);
return
task
;
}
//-----------------------------------------------------------------------------
QGCTileSet
QGCTileSet
QGCMapEngine
::
getTileCount
(
int
zoom
,
double
topleftLon
,
double
topleftLat
,
double
bottomRightLon
,
double
bottomRightLat
,
QString
mapType
)
{
if
(
zoom
<
1
)
zoom
=
1
;
if
(
zoom
>
MAX_MAP_ZOOM
)
zoom
=
MAX_MAP_ZOOM
;
QGCTileSet
set
;
set
.
tileX0
=
getQGCMapEngine
()
->
urlFactory
()
->
long2tileX
(
mapType
,
topleftLon
,
zoom
);
set
.
tileY0
=
getQGCMapEngine
()
->
urlFactory
()
->
lat2tileY
(
mapType
,
topleftLat
,
zoom
);
set
.
tileX1
=
getQGCMapEngine
()
->
urlFactory
()
->
long2tileX
(
mapType
,
bottomRightLon
,
zoom
);
set
.
tileY1
=
getQGCMapEngine
()
->
urlFactory
()
->
lat2tileY
(
mapType
,
bottomRightLat
,
zoom
);
set
.
tileCount
=
(
static_cast
<
quint64
>
(
set
.
tileX1
)
-
static_cast
<
quint64
>
(
set
.
tileX0
)
+
1
)
*
(
static_cast
<
quint64
>
(
set
.
tileY1
)
-
static_cast
<
quint64
>
(
set
.
tileY0
)
+
1
);
set
.
tileSize
=
getQGCMapEngine
()
->
urlFactory
()
->
averageSizeForType
(
mapType
)
*
set
.
tileCount
;
return
set
;
if
(
zoom
<
1
)
zoom
=
1
;
if
(
zoom
>
MAX_MAP_ZOOM
)
zoom
=
MAX_MAP_ZOOM
;
QGCTileSet
set
;
if
(
mapType
!=
"Airmap Elevation"
){
set
.
tileX0
=
getQGCMapEngine
()
->
urlFactory
()
->
long2tileX
(
mapType
,
topleftLon
,
zoom
);
set
.
tileY0
=
getQGCMapEngine
()
->
urlFactory
()
->
lat2tileY
(
mapType
,
topleftLat
,
zoom
);
set
.
tileX1
=
getQGCMapEngine
()
->
urlFactory
()
->
long2tileX
(
mapType
,
bottomRightLon
,
zoom
);
set
.
tileY1
=
getQGCMapEngine
()
->
urlFactory
()
->
lat2tileY
(
mapType
,
bottomRightLat
,
zoom
);
}
else
{
set
.
tileX0
=
getQGCMapEngine
()
->
urlFactory
()
->
long2tileX
(
mapType
,
topleftLon
,
zoom
);
set
.
tileY0
=
getQGCMapEngine
()
->
urlFactory
()
->
lat2tileY
(
mapType
,
bottomRightLat
,
zoom
);
set
.
tileX1
=
getQGCMapEngine
()
->
urlFactory
()
->
long2tileX
(
mapType
,
bottomRightLon
,
zoom
);
set
.
tileY1
=
getQGCMapEngine
()
->
urlFactory
()
->
lat2tileY
(
mapType
,
topleftLat
,
zoom
);
}
set
.
tileCount
=
(
static_cast
<
quint64
>
(
set
.
tileX1
)
-
static_cast
<
quint64
>
(
set
.
tileX0
)
+
1
)
*
(
static_cast
<
quint64
>
(
set
.
tileY1
)
-
static_cast
<
quint64
>
(
set
.
tileY0
)
+
1
);
qDebug
()
<<
"getTileCount : "
<<
set
.
tileCount
;
set
.
tileSize
=
getQGCMapEngine
()
->
urlFactory
()
->
averageSizeForType
(
mapType
)
*
set
.
tileCount
;
return
set
;
}
...
...
src/QtLocationPlugin/QGCMapUrlEngine.cpp
View file @
5ba79984
...
...
@@ -72,6 +72,8 @@ UrlFactory::UrlFactory() : _timeout(5 * 1000) {
_providersTable
[
"VWorld Street Map"
]
=
new
VWorldStreetMapProvider
(
this
);
_providersTable
[
"VWorld Satellite Map"
]
=
new
VWorldSatMapProvider
(
this
);
_providersTable
[
"Airmap Elevation"
]
=
new
AirmapElevationProvider
(
this
);
}
void
UrlFactory
::
registerProvider
(
QString
name
,
MapProvider
*
provider
)
{
...
...
@@ -121,16 +123,6 @@ QNetworkRequest UrlFactory::getTileURL(QString type, int x, int y, int zoom,
qCDebug
(
QGCMapUrlEngineLog
)
<<
"getTileURL : map not registered :"
<<
type
;
return
QNetworkRequest
(
QUrl
());
}
#if 0
case AirmapElevation:
{
}
break;
//-----------------------------------------------------------------------------
#endif
//-----------------------------------------------------------------------------
quint32
UrlFactory
::
averageSizeForType
(
QString
type
)
{
...
...
src/QtLocationPlugin/QGCMapUrlEngine.h
View file @
5ba79984
...
...
@@ -22,6 +22,7 @@
#include "GenericMapProvider.h"
#include "EsriMapProvider.h"
#include "MapboxMapProvider.h"
#include "ElevationMapProvider.h"
#define MAX_MAP_ZOOM (20.0)
...
...
src/QtLocationPlugin/QMLControl/OfflineMap.qml
View file @
5ba79984
...
...
@@ -463,7 +463,7 @@ Item {
Row
{
spacing
:
ScreenTools
.
defaultFontPixelWidth
anchors.horizontalCenter
:
parent
.
horizontalCenter
visible
:
!
_defaultSet
&&
mapType
!==
"
Airmap Elevation
Data
"
visible
:
!
_defaultSet
&&
mapType
!==
"
Airmap Elevation
"
QGCLabel
{
text
:
qsTr
(
"
Zoom Levels:
"
);
width
:
infoView
.
_labelWidth
;
}
QGCLabel
{
text
:
offlineMapView
.
_currentSelection
?
(
offlineMapView
.
_currentSelection
.
minZoom
+
"
-
"
+
offlineMapView
.
_currentSelection
.
maxZoom
)
:
""
;
horizontalAlignment
:
Text
.
AlignRight
;
width
:
infoView
.
_valueWidth
;
}
}
...
...
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc
View file @
5ba79984
...
...
@@ -233,7 +233,6 @@ QGCMapEngineManager::mapTypeList(QString provider)
{
// Extract type name from MapName ( format : "Provider Type")
QStringList
mapList
=
getQGCMapEngine
()
->
getMapNameList
();
qDebug
()
<<
"mapTypeList : "
<<
provider
;
mapList
=
mapList
.
filter
(
QRegularExpression
(
provider
));
mapList
.
replaceInStrings
(
QRegExp
(
"^([^
\\
]*) (.*)$"
),
"
\\
2"
);
mapList
.
removeDuplicates
();
...
...
src/Terrain/TerrainQuery.cc
View file @
5ba79984
...
...
@@ -426,13 +426,13 @@ bool TerrainTileManager::_getAltitudesForCoordinates(const QList<QGeoCoordinate>
}
}
else
{
if
(
_state
!=
State
::
Downloading
)
{
QNetworkRequest
request
=
getQGCMapEngine
()
->
urlFactory
()
->
getTileURL
(
"AirmapElevation"
,
getQGCMapEngine
()
->
urlFactory
()
->
long2tileX
(
"Airmap Elevation"
,
coordinate
.
longitude
(),
1
),
getQGCMapEngine
()
->
urlFactory
()
->
lat2tileY
(
"Airmap Elevation"
,
coordinate
.
latitude
(),
1
),
1
,
&
_networkManager
);
QNetworkRequest
request
=
getQGCMapEngine
()
->
urlFactory
()
->
getTileURL
(
"Airmap
Elevation"
,
getQGCMapEngine
()
->
urlFactory
()
->
long2tileX
(
"Airmap Elevation"
,
coordinate
.
longitude
(),
1
),
getQGCMapEngine
()
->
urlFactory
()
->
lat2tileY
(
"Airmap Elevation"
,
coordinate
.
latitude
(),
1
),
1
,
&
_networkManager
);
qCDebug
(
TerrainQueryLog
)
<<
"TerrainTileManager::_getAltitudesForCoordinates query from database"
<<
request
.
url
();
QGeoTileSpec
spec
;
spec
.
setX
(
getQGCMapEngine
()
->
urlFactory
()
->
long2tileX
(
"Airmap Elevation"
,
coordinate
.
longitude
(),
1
));
spec
.
setY
(
getQGCMapEngine
()
->
urlFactory
()
->
lat2tileY
(
"Airmap Elevation"
,
coordinate
.
latitude
(),
1
));
spec
.
setZoom
(
1
);
spec
.
setMapId
(
getQGCMapEngine
()
->
urlFactory
()
->
getIdFromType
(
"AirmapElevation"
));
spec
.
setMapId
(
getQGCMapEngine
()
->
urlFactory
()
->
getIdFromType
(
"Airmap
Elevation"
));
QGeoTiledMapReplyQGC
*
reply
=
new
QGeoTiledMapReplyQGC
(
&
_networkManager
,
request
,
spec
);
connect
(
reply
,
&
QGeoTiledMapReplyQGC
::
terrainDone
,
this
,
&
TerrainTileManager
::
_terrainDone
);
_state
=
State
::
Downloading
;
...
...
@@ -473,7 +473,7 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N
// remove from download queue
QGeoTileSpec
spec
=
reply
->
tileSpec
();
QString
hash
=
QGCMapEngine
::
getTileHash
(
"AirmapElevation"
,
spec
.
x
(),
spec
.
y
(),
spec
.
zoom
());
QString
hash
=
QGCMapEngine
::
getTileHash
(
"Airmap
Elevation"
,
spec
.
x
(),
spec
.
y
(),
spec
.
zoom
());
// handle potential errors
if
(
error
!=
QNetworkReply
::
NoError
)
{
...
...
@@ -539,7 +539,11 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N
QString
TerrainTileManager
::
_getTileHash
(
const
QGeoCoordinate
&
coordinate
)
{
QString
ret
=
QGCMapEngine
::
getTileHash
(
"AirmapElevation"
,
getQGCMapEngine
()
->
urlFactory
()
->
long2tileX
(
"Airmap Elevation"
,
coordinate
.
longitude
(),
1
),
getQGCMapEngine
()
->
urlFactory
()
->
lat2tileY
(
"Airmap Elevation"
,
coordinate
.
latitude
(),
1
),
1
);
QString
ret
=
QGCMapEngine
::
getTileHash
(
"Airmap Elevation"
,
getQGCMapEngine
()
->
urlFactory
()
->
long2tileX
(
"Airmap Elevation"
,
coordinate
.
longitude
(),
1
),
getQGCMapEngine
()
->
urlFactory
()
->
lat2tileY
(
"Airmap Elevation"
,
coordinate
.
latitude
(),
1
),
1
);
qCDebug
(
TerrainQueryVerboseLog
)
<<
"Computing unique tile hash for "
<<
coordinate
<<
ret
;
return
ret
;
...
...
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