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
abe232e0
Commit
abe232e0
authored
Sep 18, 2019
by
Pierre TILAK
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Add Elevation, lat2tile in MapProvider
parent
fa4c3b5e
Changes
16
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
16 changed files
with
148 additions
and
389 deletions
+148
-389
MissionController.cc
src/MissionManager/MissionController.cc
+2
-2
ElevationMapProvider.cpp
src/QtLocationPlugin/ElevationMapProvider.cpp
+40
-0
ElevationMapProvider.h
src/QtLocationPlugin/ElevationMapProvider.h
+47
-0
MapProvider.cpp
src/QtLocationPlugin/MapProvider.cpp
+12
-0
MapProvider.h
src/QtLocationPlugin/MapProvider.h
+4
-3
MapboxMapProvider.h
src/QtLocationPlugin/MapboxMapProvider.h
+3
-0
QGCLocationPlugin.pri
src/QtLocationPlugin/QGCLocationPlugin.pri
+2
-0
QGCMapEngine.cpp
src/QtLocationPlugin/QGCMapEngine.cpp
+4
-43
QGCMapEngine.h
src/QtLocationPlugin/QGCMapEngine.h
+1
-8
QGCMapTileSet.cpp
src/QtLocationPlugin/QGCMapTileSet.cpp
+1
-1
QGCMapUrlEngine.cpp
src/QtLocationPlugin/QGCMapUrlEngine.cpp
+15
-300
QGCMapUrlEngine.h
src/QtLocationPlugin/QGCMapUrlEngine.h
+3
-16
QGeoMapReplyQGC.cpp
src/QtLocationPlugin/QGeoMapReplyQGC.cpp
+5
-5
QGeoTiledMappingManagerEngineQGC.cpp
src/QtLocationPlugin/QGeoTiledMappingManagerEngineQGC.cpp
+1
-3
QGCMapEngineManager.cc
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc
+4
-4
TerrainQuery.cc
src/Terrain/TerrainQuery.cc
+4
-4
No files found.
src/MissionManager/MissionController.cc
View file @
abe232e0
...
...
@@ -412,8 +412,8 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate
// If the ComplexMissionItem is inserted first, add a TakeOff SimpleMissionItem
if
(
_visualItems
->
count
()
==
1
&&
(
_controllerVehicle
->
fixedWing
()
||
_controllerVehicle
->
vtol
()
||
_controllerVehicle
->
multiRotor
()))
{
insertSimpleMissionItem
(
mapCenterCoordinate
,
i
);
i
++
;
insertSimpleMissionItem
(
mapCenterCoordinate
,
visualItemIndex
);
visualItemIndex
++
;
}
int
sequenceNumber
=
_nextSequenceNumber
();
...
...
src/QtLocationPlugin/ElevationMapProvider.cpp
0 → 100644
View file @
abe232e0
#include "ElevationMapProvider.h"
#if defined(DEBUG_GOOGLE_MAPS)
#include <QFile>
#include <QStandardPaths>
#endif
#include "QGCMapEngine.h"
ElevationProvider
::
ElevationProvider
(
QString
imageFormat
,
quint32
averageSize
,
QGeoMapType
::
MapStyle
mapType
,
QObject
*
parent
)
:
MapProvider
(
QString
(
"https://api.airmap.com/"
),
imageFormat
,
averageSize
,
mapType
,
parent
)
{}
ElevationProvider
::~
ElevationProvider
()
{}
//-----------------------------------------------------------------------------
int
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
)
{
Q_UNUSED
(
z
);
return
static_cast
<
int
>
(
floor
((
lat
+
90.0
)
/
srtm1TileSize
));
}
QString
AirmapElevationProvider
::
_getURL
(
int
x
,
int
y
,
int
zoom
,
QNetworkAccessManager
*
networkManager
)
{
Q_UNUSED
(
networkManager
);
Q_UNUSED
(
zoom
);
return
QString
(
"https://api.airmap.com/elevation/v1/ele/"
"carpet?points=%1,%2,%3,%4"
)
.
arg
(
static_cast
<
double
>
(
y
)
*
srtm1TileSize
-
90.0
)
.
arg
(
static_cast
<
double
>
(
x
)
*
srtm1TileSize
-
180.0
)
.
arg
(
static_cast
<
double
>
(
y
+
1
)
*
srtm1TileSize
-
90.0
)
.
arg
(
static_cast
<
double
>
(
x
+
1
)
*
srtm1TileSize
-
180.0
);
}
src/QtLocationPlugin/ElevationMapProvider.h
0 → 100644
View file @
abe232e0
#pragma once
#include "MapProvider.h"
#include <QByteArray>
#include <QMutex>
#include <QNetworkProxy>
#include <QNetworkReply>
#include <QPoint>
#include <QString>
const
quint32
AVERAGE_AIRMAP_ELEV_SIZE
=
2786
;
//-----------------------------------------------------------------------------
const
double
srtm1TileSize
=
0
.
01
;
class
ElevationProvider
:
public
MapProvider
{
Q_OBJECT
public:
ElevationProvider
(
QString
imageFormat
,
quint32
averageSize
,
QGeoMapType
::
MapStyle
mapType
,
QObject
*
parent
);
~
ElevationProvider
();
int
long2tileX
(
double
lon
,
int
z
);
int
lat2tileY
(
double
lat
,
int
z
);
protected:
// Define the url to Request
virtual
QString
_getURL
(
int
x
,
int
y
,
int
zoom
,
QNetworkAccessManager
*
networkManager
)
=
0
;
};
// -----------------------------------------------------------
// Airmap Elevation
class
AirmapElevationProvider
:
public
ElevationProvider
{
Q_OBJECT
public:
AirmapElevationProvider
(
QObject
*
parent
)
:
ElevationProvider
(
QString
(
"bin"
),
AVERAGE_AIRMAP_ELEV_SIZE
,
QGeoMapType
::
StreetMap
,
parent
)
{}
protected:
QString
_getURL
(
int
x
,
int
y
,
int
zoom
,
QNetworkAccessManager
*
networkManager
);
};
src/QtLocationPlugin/MapProvider.cpp
View file @
abe232e0
...
...
@@ -61,3 +61,15 @@ QString MapProvider::_tileXYToQuadKey(int tileX, int tileY, int levelOfDetail) {
int
MapProvider
::
_getServerNum
(
int
x
,
int
y
,
int
max
)
{
return
(
x
+
2
*
y
)
%
max
;
}
int
MapProvider
::
long2tileX
(
double
lon
,
int
z
)
{
return
static_cast
<
int
>
(
floor
((
lon
+
180.0
)
/
360.0
*
pow
(
2.0
,
z
)));
}
//-----------------------------------------------------------------------------
int
MapProvider
::
lat2tileY
(
double
lat
,
int
z
)
{
return
static_cast
<
int
>
(
floor
(
(
1.0
-
log
(
tan
(
lat
*
M_PI
/
180.0
)
+
1.0
/
cos
(
lat
*
M_PI
/
180.0
))
/
M_PI
)
/
2.0
*
pow
(
2.0
,
z
)));
}
src/QtLocationPlugin/MapProvider.h
View file @
abe232e0
...
...
@@ -11,10 +11,7 @@ static const unsigned char pngSignature[] = {0x89, 0x50, 0x4E, 0x47, 0x0D,
static
const
unsigned
char
jpegSignature
[]
=
{
0xFF
,
0xD8
,
0xFF
,
0x00
};
static
const
unsigned
char
gifSignature
[]
=
{
0x47
,
0x49
,
0x46
,
0x38
,
0x00
};
const
quint32
AVERAGE_MAPBOX_SAT_MAP
=
15739
;
const
quint32
AVERAGE_MAPBOX_STREET_MAP
=
5648
;
const
quint32
AVERAGE_TILE_SIZE
=
13652
;
const
quint32
AVERAGE_AIRMAP_ELEV_SIZE
=
2786
;
class
MapProvider
:
public
QObject
{
Q_OBJECT
...
...
@@ -32,6 +29,10 @@ class MapProvider : public QObject {
QGeoMapType
::
MapStyle
getMapStyle
(){
return
_mapType
;}
int
long2tileX
(
double
lon
,
int
z
);
int
lat2tileY
(
double
lat
,
int
z
);
protected:
QString
_tileXYToQuadKey
(
int
tileX
,
int
tileY
,
int
levelOfDetail
);
int
_getServerNum
(
int
x
,
int
y
,
int
max
);
...
...
src/QtLocationPlugin/MapboxMapProvider.h
View file @
abe232e0
...
...
@@ -9,6 +9,9 @@
#include <QPoint>
#include <QString>
const
quint32
AVERAGE_MAPBOX_SAT_MAP
=
15739
;
const
quint32
AVERAGE_MAPBOX_STREET_MAP
=
5648
;
class
MapboxMapProvider
:
public
MapProvider
{
Q_OBJECT
public:
...
...
src/QtLocationPlugin/QGCLocationPlugin.pri
View file @
abe232e0
...
...
@@ -23,6 +23,7 @@ HEADERS += \
$$PWD/QGeoTileFetcherQGC.h \
$$PWD/QGeoTiledMappingManagerEngineQGC.h \
$$PWD/MapProvider.h \
$$PWD/ElevationMapProvider.h \
$$PWD/GoogleMapProvider.h \
$$PWD/BingMapProvider.h \
$$PWD/GenericMapProvider.h \
...
...
@@ -41,6 +42,7 @@ SOURCES += \
$$PWD/QGeoTileFetcherQGC.cpp \
$$PWD/QGeoTiledMappingManagerEngineQGC.cpp \
$$PWD/MapProvider.cpp \
$$PWD/ElevationMapProvider.cpp \
$$PWD/GoogleMapProvider.cpp \
$$PWD/BingMapProvider.cpp \
$$PWD/GenericMapProvider.cpp \
...
...
src/QtLocationPlugin/QGCMapEngine.cpp
View file @
abe232e0
...
...
@@ -56,9 +56,6 @@ getQGCMapEngine()
return
kMapEngine
;
}
//-----------------------------------------------------------------------------
const
double
QGCMapEngine
::
srtm1TileSize
=
0.01
;
//-----------------------------------------------------------------------------
void
destroyMapEngine
()
...
...
@@ -254,51 +251,15 @@ QGCMapEngine::getTileCount(int zoom, double topleftLon, double topleftLat, doubl
if
(
zoom
<
1
)
zoom
=
1
;
if
(
zoom
>
MAX_MAP_ZOOM
)
zoom
=
MAX_MAP_ZOOM
;
QGCTileSet
set
;
if
(
mapType
!=
"AirmapElevation"
)
{
set
.
tileX0
=
long2tileX
(
topleftLon
,
zoom
);
set
.
tileY0
=
lat2tileY
(
topleftLat
,
zoom
);
set
.
tileX1
=
long2tileX
(
bottomRightLon
,
zoom
);
set
.
tileY1
=
lat2tileY
(
bottomRightLat
,
zoom
);
}
else
{
set
.
tileX0
=
long2elevationTileX
(
topleftLon
,
zoom
);
set
.
tileY0
=
lat2elevationTileY
(
bottomRightLat
,
zoom
);
set
.
tileX1
=
long2elevationTileX
(
bottomRightLon
,
zoom
);
set
.
tileY1
=
lat2elevationTileY
(
topleftLat
,
zoom
);
}
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
;
}
//-----------------------------------------------------------------------------
int
QGCMapEngine
::
long2tileX
(
double
lon
,
int
z
)
{
return
static_cast
<
int
>
(
floor
((
lon
+
180.0
)
/
360.0
*
pow
(
2.0
,
z
)));
}
//-----------------------------------------------------------------------------
int
QGCMapEngine
::
lat2tileY
(
double
lat
,
int
z
)
{
return
static_cast
<
int
>
(
floor
((
1.0
-
log
(
tan
(
lat
*
M_PI
/
180.0
)
+
1.0
/
cos
(
lat
*
M_PI
/
180.0
))
/
M_PI
)
/
2.0
*
pow
(
2.0
,
z
)));
}
//-----------------------------------------------------------------------------
int
QGCMapEngine
::
long2elevationTileX
(
double
lon
,
int
z
)
{
Q_UNUSED
(
z
);
return
static_cast
<
int
>
(
floor
((
lon
+
180.0
)
/
srtm1TileSize
));
}
//-----------------------------------------------------------------------------
int
QGCMapEngine
::
lat2elevationTileY
(
double
lat
,
int
z
)
{
Q_UNUSED
(
z
);
return
static_cast
<
int
>
(
floor
((
lat
+
90.0
)
/
srtm1TileSize
));
}
//-----------------------------------------------------------------------------
QStringList
...
...
src/QtLocationPlugin/QGCMapEngine.h
View file @
abe232e0
...
...
@@ -92,20 +92,13 @@ public:
//-- Tile Math
static
QGCTileSet
getTileCount
(
int
zoom
,
double
topleftLon
,
double
topleftLat
,
double
bottomRightLon
,
double
bottomRightLat
,
QString
mapType
);
static
int
long2tileX
(
double
lon
,
int
z
);
static
int
lat2tileY
(
double
lat
,
int
z
);
static
int
long2elevationTileX
(
double
lon
,
int
z
);
static
int
lat2elevationTileY
(
double
lat
,
int
z
);
static
QString
getTileHash
(
QString
type
,
int
x
,
int
y
,
int
z
);
static
QString
getTypeFromName
(
const
QString
&
name
);
static
QString
getTypeFromName
(
const
QString
&
name
);
static
QString
bigSizeToString
(
quint64
size
);
static
QString
storageFreeSizeToString
(
quint64
size_MB
);
static
QString
numberToString
(
quint64
number
);
static
int
concurrentDownloads
(
QString
type
);
/// size of an elevation tile in degree
static
const
double
srtm1TileSize
;
private
slots
:
void
_updateTotals
(
quint32
totaltiles
,
quint64
totalsize
,
quint32
defaulttiles
,
quint64
defaultsize
);
void
_pruned
();
...
...
src/QtLocationPlugin/QGCMapTileSet.cpp
View file @
abe232e0
...
...
@@ -280,7 +280,7 @@ QGCCachedTileSet::_networkReplyFinished()
qCDebug
(
QGCCachedTileSetLog
)
<<
"Tile fetched"
<<
hash
;
QByteArray
image
=
reply
->
readAll
();
QString
type
=
getQGCMapEngine
()
->
hashToType
(
hash
);
if
(
type
==
"AirmapElevation"
)
{
if
(
type
==
"Airmap
Elevation"
)
{
image
=
TerrainTile
::
serialize
(
image
);
}
QString
format
=
getQGCMapEngine
()
->
urlFactory
()
->
getImageFormat
(
type
,
image
);
...
...
src/QtLocationPlugin/QGCMapUrlEngine.cpp
View file @
abe232e0
This diff is collapsed.
Click to expand it.
src/QtLocationPlugin/QGCMapUrlEngine.h
View file @
abe232e0
...
...
@@ -28,18 +28,6 @@
class
UrlFactory
:
public
QObject
{
Q_OBJECT
public:
//
// /*
// MapQuestMap = 700,
// MapQuestSat = 701,
// */
//
// VWorldMap = 800,
// VWorldSatellite = 801,
// VWorldStreet = 802,
//
// AirmapElevation = 8001
// };
UrlFactory
();
~
UrlFactory
();
...
...
@@ -52,6 +40,9 @@ public:
quint32
averageSizeForType
(
QString
type
);
int
long2tileX
(
QString
mapType
,
double
lon
,
int
z
);
int
lat2tileY
(
QString
mapType
,
double
lat
,
int
z
);
QHash
<
QString
,
MapProvider
*>
getProviderTable
(){
return
_providersTable
;}
int
getIdFromType
(
QString
type
);
...
...
@@ -62,10 +53,6 @@ private:
QHash
<
QString
,
MapProvider
*>
_providersTable
;
void
registerProvider
(
QString
Name
,
MapProvider
*
provider
);
// BingMaps
//QString _versionBingMaps;
};
#endif
src/QtLocationPlugin/QGeoMapReplyQGC.cpp
View file @
abe232e0
...
...
@@ -124,12 +124,12 @@ QGeoTiledMapReplyQGC::networkReplyFinished()
QByteArray
a
=
_reply
->
readAll
();
QString
format
=
getQGCMapEngine
()
->
urlFactory
()
->
getImageFormat
(
tileSpec
().
mapId
(),
a
);
//-- Test for a specialized, elevation data (not map tile)
int
AirmapElevationId
=
getQGCMapEngine
()
->
urlFactory
()
->
getIdFromType
(
"AirmapElevation"
);
int
AirmapElevationId
=
getQGCMapEngine
()
->
urlFactory
()
->
getIdFromType
(
"Airmap
Elevation"
);
if
(
tileSpec
().
mapId
()
==
AirmapElevationId
)
{
a
=
TerrainTile
::
serialize
(
a
);
//-- Cache it if valid
if
(
!
a
.
isEmpty
())
{
getQGCMapEngine
()
->
cacheTile
(
"AirmapElevation"
,
tileSpec
().
x
(),
tileSpec
().
y
(),
tileSpec
().
zoom
(),
a
,
format
);
getQGCMapEngine
()
->
cacheTile
(
"Airmap
Elevation"
,
tileSpec
().
x
(),
tileSpec
().
y
(),
tileSpec
().
zoom
(),
a
,
format
);
}
emit
terrainDone
(
a
,
QNetworkReply
::
NoError
);
}
else
{
...
...
@@ -153,7 +153,7 @@ QGeoTiledMapReplyQGC::networkReplyError(QNetworkReply::NetworkError error)
return
;
}
//-- Test for a specialized, elevation data (not map tile)
int
AirmapElevationId
=
getQGCMapEngine
()
->
urlFactory
()
->
getIdFromType
(
"AirmapElevation"
);
int
AirmapElevationId
=
getQGCMapEngine
()
->
urlFactory
()
->
getIdFromType
(
"Airmap
Elevation"
);
if
(
tileSpec
().
mapId
()
==
AirmapElevationId
)
{
emit
terrainDone
(
QByteArray
(),
error
);
}
else
{
...
...
@@ -172,7 +172,7 @@ void
QGeoTiledMapReplyQGC
::
cacheError
(
QGCMapTask
::
TaskType
type
,
QString
/*errorString*/
)
{
if
(
!
getQGCMapEngine
()
->
isInternetActive
())
{
int
AirmapElevationId
=
getQGCMapEngine
()
->
urlFactory
()
->
getIdFromType
(
"AirmapElevation"
);
int
AirmapElevationId
=
getQGCMapEngine
()
->
urlFactory
()
->
getIdFromType
(
"Airmap
Elevation"
);
if
(
tileSpec
().
mapId
()
==
AirmapElevationId
)
{
emit
terrainDone
(
QByteArray
(),
QNetworkReply
::
NetworkSessionFailedError
);
}
else
{
...
...
@@ -210,7 +210,7 @@ void
QGeoTiledMapReplyQGC
::
cacheReply
(
QGCCacheTile
*
tile
)
{
//-- Test for a specialized, elevation data (not map tile)
int
AirmapElevationId
=
getQGCMapEngine
()
->
urlFactory
()
->
getIdFromType
(
"AirmapElevation"
);
int
AirmapElevationId
=
getQGCMapEngine
()
->
urlFactory
()
->
getIdFromType
(
"Airmap
Elevation"
);
if
(
tileSpec
().
mapId
()
==
AirmapElevationId
)
{
emit
terrainDone
(
tile
->
img
(),
QNetworkReply
::
NoError
);
}
else
{
...
...
src/QtLocationPlugin/QGeoTiledMappingManagerEngineQGC.cpp
View file @
abe232e0
...
...
@@ -106,12 +106,10 @@ QGeoTiledMappingManagerEngineQGC::QGeoTiledMappingManagerEngineQGC(const QVarian
while
(
i
.
hasNext
()){
i
.
next
();
qDebug
()
<<
"Add MapProvider"
<<
i
.
value
()
->
getMapStyle
()
<<
i
.
key
()
<<
getQGCMapEngine
()
->
urlFactory
()
->
getIdFromType
(
i
.
key
());
mapList
.
append
(
QGCGEOMAPTYPE
(
i
.
value
()
->
getMapStyle
(),
i
.
key
(),
i
.
key
(),
false
,
false
,
getQGCMapEngine
()
->
urlFactory
()
->
getIdFromType
(
i
.
key
())
));
}
setSupportedMapTypes
(
mapList
);
qDebug
()
<<
"End Adding Provider"
;
//-- Users (QML code) can define a different user agent
if
(
parameters
.
contains
(
QStringLiteral
(
"useragent"
)))
{
getQGCMapEngine
()
->
setUserAgent
(
parameters
.
value
(
QStringLiteral
(
"useragent"
)).
toString
().
toLatin1
());
...
...
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc
View file @
abe232e0
...
...
@@ -84,7 +84,7 @@ QGCMapEngineManager::updateForCurrentView(double lon0, double lat0, double lon1,
_imageSet
+=
set
;
}
if
(
_fetchElevation
)
{
QGCTileSet
set
=
QGCMapEngine
::
getTileCount
(
1
,
lon0
,
lat0
,
lon1
,
lat1
,
"AirmapElevation"
);
QGCTileSet
set
=
QGCMapEngine
::
getTileCount
(
1
,
lon0
,
lat0
,
lon1
,
lat1
,
"Airmap
Elevation"
);
_elevationSet
+=
set
;
}
...
...
@@ -159,9 +159,9 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType)
}
else
{
qWarning
()
<<
"QGCMapEngineManager::startDownload() No Tiles to save"
;
}
if
(
mapType
!=
"Airmap Elevation
Data
"
&&
_fetchElevation
)
{
if
(
mapType
!=
"Airmap Elevation"
&&
_fetchElevation
)
{
QGCCachedTileSet
*
set
=
new
QGCCachedTileSet
(
name
+
" Elevation"
);
set
->
setMapTypeStr
(
"Airmap Elevation
Data
"
);
set
->
setMapTypeStr
(
"Airmap Elevation"
);
set
->
setTopleftLat
(
_topleftLat
);
set
->
setTopleftLon
(
_topleftLon
);
set
->
setBottomRightLat
(
_bottomRightLat
);
...
...
@@ -170,7 +170,7 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType)
set
->
setMaxZoom
(
1
);
set
->
setTotalTileSize
(
_elevationSet
.
tileSize
);
set
->
setTotalTileCount
(
static_cast
<
quint32
>
(
_elevationSet
.
tileCount
));
set
->
setType
(
"AirmapElevation"
);
set
->
setType
(
"Airmap
Elevation"
);
QGCCreateTileSetTask
*
task
=
new
QGCCreateTileSetTask
(
set
);
//-- Create Tile Set (it will also create a list of tiles to download)
connect
(
task
,
&
QGCCreateTileSetTask
::
tileSetSaved
,
this
,
&
QGCMapEngineManager
::
_tileSetSaved
);
...
...
src/Terrain/TerrainQuery.cc
View file @
abe232e0
...
...
@@ -426,11 +426,11 @@ bool TerrainTileManager::_getAltitudesForCoordinates(const QList<QGeoCoordinate>
}
}
else
{
if
(
_state
!=
State
::
Downloading
)
{
QNetworkRequest
request
=
getQGCMapEngine
()
->
urlFactory
()
->
getTileURL
(
"AirmapElevation"
,
QGCMapEngine
::
long2elevationTileX
(
coordinate
.
longitude
(),
1
),
QGCMapEngine
::
lat2elevationTileY
(
coordinate
.
latitude
(),
1
),
1
,
&
_networkManager
);
QNetworkRequest
request
=
getQGCMapEngine
()
->
urlFactory
()
->
getTileURL
(
"AirmapElevation"
,
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
(
QGCMapEngine
::
long2elevationTileX
(
coordinate
.
longitude
(),
1
));
spec
.
setY
(
QGCMapEngine
::
lat2elevationTileY
(
coordinate
.
latitude
(),
1
));
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"
));
QGeoTiledMapReplyQGC
*
reply
=
new
QGeoTiledMapReplyQGC
(
&
_networkManager
,
request
,
spec
);
...
...
@@ -539,7 +539,7 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N
QString
TerrainTileManager
::
_getTileHash
(
const
QGeoCoordinate
&
coordinate
)
{
QString
ret
=
QGCMapEngine
::
getTileHash
(
"AirmapElevation"
,
QGCMapEngine
::
long2elevationTileX
(
coordinate
.
longitude
(),
1
),
QGCMapEngine
::
lat2elevationTileY
(
coordinate
.
latitude
(),
1
),
1
);
QString
ret
=
QGCMapEngine
::
getTileHash
(
"AirmapElevation"
,
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