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
0b0b4757
Commit
0b0b4757
authored
Oct 29, 2010
by
pixhawk
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'master' of pixhawk.ethz.ch:qgroundcontrol
parents
3ad00a0d
1dc379f0
Changes
7
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
146 additions
and
40 deletions
+146
-40
Imagery.cc
src/ui/map3D/Imagery.cc
+82
-27
Imagery.h
src/ui/map3D/Imagery.h
+5
-3
Q3DWidget.cc
src/ui/map3D/Q3DWidget.cc
+5
-3
QMap3DWidget.cc
src/ui/map3D/QMap3DWidget.cc
+12
-2
WebImage.cc
src/ui/map3D/WebImage.cc
+24
-3
WebImage.h
src/ui/map3D/WebImage.h
+2
-1
WebImageCache.cc
src/ui/map3D/WebImageCache.cc
+16
-1
No files found.
src/ui/map3D/Imagery.cc
View file @
0b0b4757
...
@@ -32,6 +32,7 @@ This file is part of the QGROUNDCONTROL project
...
@@ -32,6 +32,7 @@ This file is part of the QGROUNDCONTROL project
#include "Imagery.h"
#include "Imagery.h"
#include <cmath>
#include <cmath>
#include <iomanip>
#include <sstream>
#include <sstream>
const
double
WGS84_A
=
6378137.0
;
const
double
WGS84_A
=
6378137.0
;
...
@@ -65,7 +66,8 @@ Imagery::prefetch2D(double windowWidth, double windowHeight,
...
@@ -65,7 +66,8 @@ Imagery::prefetch2D(double windowWidth, double windowHeight,
const
QString
&
utmZone
)
const
QString
&
utmZone
)
{
{
double
tileResolution
;
double
tileResolution
;
if
(
currentImageryType
==
SATELLITE
)
if
(
currentImageryType
==
GOOGLE_SATELLITE
||
currentImageryType
==
GOOGLE_MAP
)
{
{
tileResolution
=
1.0
;
tileResolution
=
1.0
;
while
(
tileResolution
*
3.0
/
2.0
<
1.0
/
zoom
)
while
(
tileResolution
*
3.0
/
2.0
<
1.0
/
zoom
)
...
@@ -77,6 +79,10 @@ Imagery::prefetch2D(double windowWidth, double windowHeight,
...
@@ -77,6 +79,10 @@ Imagery::prefetch2D(double windowWidth, double windowHeight,
tileResolution
=
512.0
;
tileResolution
=
512.0
;
}
}
}
}
else
if
(
currentImageryType
==
SWISSTOPO_SATELLITE
)
{
tileResolution
=
0.25
;
}
int32_t
minTileX
,
minTileY
,
maxTileX
,
maxTileY
;
int32_t
minTileX
,
minTileY
,
maxTileX
,
maxTileY
;
int32_t
zoomLevel
;
int32_t
zoomLevel
;
...
@@ -92,7 +98,7 @@ Imagery::prefetch2D(double windowWidth, double windowHeight,
...
@@ -92,7 +98,7 @@ Imagery::prefetch2D(double windowWidth, double windowHeight,
{
{
for
(
int32_t
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
for
(
int32_t
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
{
QString
url
=
getTile
URL
(
c
,
r
,
zoomLevel
);
QString
url
=
getTile
Location
(
c
,
r
,
zoomLevel
,
tileResolution
);
TexturePtr
t
=
textureCache
->
get
(
url
);
TexturePtr
t
=
textureCache
->
get
(
url
);
}
}
...
@@ -106,7 +112,8 @@ Imagery::draw2D(double windowWidth, double windowHeight,
...
@@ -106,7 +112,8 @@ Imagery::draw2D(double windowWidth, double windowHeight,
const
QString
&
utmZone
)
const
QString
&
utmZone
)
{
{
double
tileResolution
;
double
tileResolution
;
if
(
currentImageryType
==
SATELLITE
)
if
(
currentImageryType
==
GOOGLE_SATELLITE
||
currentImageryType
==
GOOGLE_MAP
)
{
{
tileResolution
=
1.0
;
tileResolution
=
1.0
;
while
(
tileResolution
*
3.0
/
2.0
<
1.0
/
zoom
)
while
(
tileResolution
*
3.0
/
2.0
<
1.0
/
zoom
)
...
@@ -118,6 +125,10 @@ Imagery::draw2D(double windowWidth, double windowHeight,
...
@@ -118,6 +125,10 @@ Imagery::draw2D(double windowWidth, double windowHeight,
tileResolution
=
512.0
;
tileResolution
=
512.0
;
}
}
}
}
else
if
(
currentImageryType
==
SWISSTOPO_SATELLITE
)
{
tileResolution
=
0.25
;
}
int32_t
minTileX
,
minTileY
,
maxTileX
,
maxTileY
;
int32_t
minTileX
,
minTileY
,
maxTileX
,
maxTileY
;
int32_t
zoomLevel
;
int32_t
zoomLevel
;
...
@@ -133,7 +144,7 @@ Imagery::draw2D(double windowWidth, double windowHeight,
...
@@ -133,7 +144,7 @@ Imagery::draw2D(double windowWidth, double windowHeight,
{
{
for
(
int32_t
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
for
(
int32_t
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
{
QString
tileURL
=
getTile
URL
(
c
,
r
,
zoomLevel
);
QString
tileURL
=
getTile
Location
(
c
,
r
,
zoomLevel
,
tileResolution
);
double
x1
,
y1
,
x2
,
y2
,
x3
,
y3
,
x4
,
y4
;
double
x1
,
y1
,
x2
,
y2
,
x3
,
y3
,
x4
,
y4
;
imageBounds
(
c
,
r
,
tileResolution
,
x1
,
y1
,
x2
,
y2
,
x3
,
y3
,
x4
,
y4
);
imageBounds
(
c
,
r
,
tileResolution
,
x1
,
y1
,
x2
,
y2
,
x3
,
y3
,
x4
,
y4
);
...
@@ -170,7 +181,7 @@ Imagery::prefetch3D(double radius, double tileResolution,
...
@@ -170,7 +181,7 @@ Imagery::prefetch3D(double radius, double tileResolution,
{
{
for
(
int32_t
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
for
(
int32_t
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
{
QString
url
=
getTile
URL
(
c
,
r
,
zoomLevel
);
QString
url
=
getTile
Location
(
c
,
r
,
zoomLevel
,
tileResolution
);
TexturePtr
t
=
textureCache
->
get
(
url
);
TexturePtr
t
=
textureCache
->
get
(
url
);
}
}
...
@@ -197,7 +208,7 @@ Imagery::draw3D(double radius, double tileResolution,
...
@@ -197,7 +208,7 @@ Imagery::draw3D(double radius, double tileResolution,
{
{
for
(
int32_t
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
for
(
int32_t
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
{
QString
tileURL
=
getTile
URL
(
c
,
r
,
zoomLevel
);
QString
tileURL
=
getTile
Location
(
c
,
r
,
zoomLevel
,
tileResolution
);
double
x1
,
y1
,
x2
,
y2
,
x3
,
y3
,
x4
,
y4
;
double
x1
,
y1
,
x2
,
y2
,
x3
,
y3
,
x4
,
y4
;
imageBounds
(
c
,
r
,
tileResolution
,
x1
,
y1
,
x2
,
y2
,
x3
,
y3
,
x4
,
y4
);
imageBounds
(
c
,
r
,
tileResolution
,
x1
,
y1
,
x2
,
y2
,
x3
,
y3
,
x4
,
y4
);
...
@@ -228,20 +239,37 @@ Imagery::imageBounds(int32_t tileX, int32_t tileY, double tileResolution,
...
@@ -228,20 +239,37 @@ Imagery::imageBounds(int32_t tileX, int32_t tileY, double tileResolution,
double
&
x1
,
double
&
y1
,
double
&
x2
,
double
&
y2
,
double
&
x1
,
double
&
y1
,
double
&
x2
,
double
&
y2
,
double
&
x3
,
double
&
y3
,
double
&
x4
,
double
&
y4
)
const
double
&
x3
,
double
&
y3
,
double
&
x4
,
double
&
y4
)
const
{
{
int32_t
zoomLevel
=
MAX_ZOOM_LEVEL
-
static_cast
<
int32_t
>
(
rint
(
log2
(
tileResolution
)));
if
(
currentImageryType
==
GOOGLE_MAP
||
int32_t
numTiles
=
static_cast
<
int32_t
>
(
exp2
(
static_cast
<
double
>
(
zoomLevel
)));
currentImageryType
==
GOOGLE_SATELLITE
)
{
int32_t
zoomLevel
=
MAX_ZOOM_LEVEL
-
static_cast
<
int32_t
>
(
rint
(
log2
(
tileResolution
)));
int32_t
numTiles
=
static_cast
<
int32_t
>
(
exp2
(
static_cast
<
double
>
(
zoomLevel
)));
double
lon1
=
tileXToLongitude
(
tileX
,
numTiles
);
double
lon1
=
tileXToLongitude
(
tileX
,
numTiles
);
double
lon2
=
tileXToLongitude
(
tileX
+
1
,
numTiles
);
double
lon2
=
tileXToLongitude
(
tileX
+
1
,
numTiles
);
double
lat1
=
tileYToLatitude
(
tileY
,
numTiles
);
double
lat1
=
tileYToLatitude
(
tileY
,
numTiles
);
double
lat2
=
tileYToLatitude
(
tileY
+
1
,
numTiles
);
double
lat2
=
tileYToLatitude
(
tileY
+
1
,
numTiles
);
QString
utmZone
;
QString
utmZone
;
LLtoUTM
(
lat1
,
lon1
,
x1
,
y1
,
utmZone
);
LLtoUTM
(
lat1
,
lon1
,
x1
,
y1
,
utmZone
);
LLtoUTM
(
lat1
,
lon2
,
x2
,
y2
,
utmZone
);
LLtoUTM
(
lat1
,
lon2
,
x2
,
y2
,
utmZone
);
LLtoUTM
(
lat2
,
lon2
,
x3
,
y3
,
utmZone
);
LLtoUTM
(
lat2
,
lon2
,
x3
,
y3
,
utmZone
);
LLtoUTM
(
lat2
,
lon1
,
x4
,
y4
,
utmZone
);
LLtoUTM
(
lat2
,
lon1
,
x4
,
y4
,
utmZone
);
}
else
if
(
currentImageryType
==
SWISSTOPO_SATELLITE
)
{
double
utmMultiplier
=
tileResolution
*
200.0
;
double
minX
=
tileX
*
utmMultiplier
;
double
maxX
=
minX
+
utmMultiplier
;
double
minY
=
tileY
*
utmMultiplier
;
double
maxY
=
minY
+
utmMultiplier
;
x1
=
maxX
;
y1
=
minY
;
x2
=
maxX
;
y2
=
maxY
;
x3
=
minX
;
y3
=
maxY
;
x4
=
minX
;
y4
=
minY
;
}
}
}
void
void
...
@@ -254,15 +282,29 @@ Imagery::tileBounds(double tileResolution,
...
@@ -254,15 +282,29 @@ Imagery::tileBounds(double tileResolution,
{
{
double
centerUtmX
=
(
maxUtmX
-
minUtmX
)
/
2.0
+
minUtmX
;
double
centerUtmX
=
(
maxUtmX
-
minUtmX
)
/
2.0
+
minUtmX
;
double
centerUtmY
=
(
maxUtmY
-
minUtmY
)
/
2.0
+
minUtmY
;
double
centerUtmY
=
(
maxUtmY
-
minUtmY
)
/
2.0
+
minUtmY
;
int32_t
centerTileX
,
centerTileY
;
int32_t
centerTileX
,
centerTileY
;
UTMtoTile
(
minUtmX
,
minUtmY
,
utmZone
,
tileResolution
,
if
(
currentImageryType
==
GOOGLE_MAP
||
minTileX
,
maxTileY
,
zoomLevel
);
currentImageryType
==
GOOGLE_SATELLITE
)
UTMtoTile
(
centerUtmX
,
centerUtmY
,
utmZone
,
tileResolution
,
{
centerTileX
,
centerTileY
,
zoomLevel
);
UTMtoTile
(
minUtmX
,
minUtmY
,
utmZone
,
tileResolution
,
UTMtoTile
(
maxUtmX
,
maxUtmY
,
utmZone
,
tileResolution
,
minTileX
,
maxTileY
,
zoomLevel
);
maxTileX
,
minTileY
,
zoomLevel
);
UTMtoTile
(
centerUtmX
,
centerUtmY
,
utmZone
,
tileResolution
,
centerTileX
,
centerTileY
,
zoomLevel
);
UTMtoTile
(
maxUtmX
,
maxUtmY
,
utmZone
,
tileResolution
,
maxTileX
,
minTileY
,
zoomLevel
);
}
else
if
(
currentImageryType
==
SWISSTOPO_SATELLITE
)
{
double
utmMultiplier
=
tileResolution
*
200
;
minTileX
=
static_cast
<
int32_t
>
(
rint
(
minUtmX
/
utmMultiplier
));
minTileY
=
static_cast
<
int32_t
>
(
rint
(
minUtmY
/
utmMultiplier
));
centerTileX
=
static_cast
<
int32_t
>
(
rint
(
centerUtmX
/
utmMultiplier
));
centerTileY
=
static_cast
<
int32_t
>
(
rint
(
centerUtmY
/
utmMultiplier
));
maxTileX
=
static_cast
<
int32_t
>
(
rint
(
maxUtmX
/
utmMultiplier
));
maxTileY
=
static_cast
<
int32_t
>
(
rint
(
maxUtmY
/
utmMultiplier
));
}
if
(
maxTileX
-
minTileX
+
1
>
14
)
if
(
maxTileX
-
minTileX
+
1
>
14
)
{
{
...
@@ -513,20 +555,33 @@ Imagery::UTMtoLL(double utmNorthing, double utmEasting, const QString& utmZone,
...
@@ -513,20 +555,33 @@ Imagery::UTMtoLL(double utmNorthing, double utmEasting, const QString& utmZone,
}
}
QString
QString
Imagery
::
getTileURL
(
int32_t
tileX
,
int32_t
tileY
,
int32_t
zoomLevel
)
const
Imagery
::
getTileLocation
(
int32_t
tileX
,
int32_t
tileY
,
int32_t
zoomLevel
,
double
tileResolution
)
const
{
{
std
::
ostringstream
oss
;
std
::
ostringstream
oss
;
switch
(
currentImageryType
)
switch
(
currentImageryType
)
{
{
case
MAP
:
case
GOOGLE_
MAP
:
oss
<<
"http://mt0.google.com/vt/lyrs=m@120&x="
<<
tileX
oss
<<
"http://mt0.google.com/vt/lyrs=m@120&x="
<<
tileX
<<
"&y="
<<
tileY
<<
"&z="
<<
zoomLevel
;
<<
"&y="
<<
tileY
<<
"&z="
<<
zoomLevel
;
break
;
break
;
case
SATELLITE
:
case
GOOGLE_
SATELLITE
:
oss
<<
"http://khm.google.com/vt/lbw/lyrs=y&x="
<<
tileX
oss
<<
"http://khm.google.com/vt/lbw/lyrs=y&x="
<<
tileX
<<
"&y="
<<
tileY
<<
"&z="
<<
zoomLevel
;
<<
"&y="
<<
tileY
<<
"&z="
<<
zoomLevel
;
break
;
break
;
case
SWISSTOPO_SATELLITE
:
oss
<<
"../map/eth_zurich_swissimage_025/200/color/"
<<
tileY
<<
"/tile-"
;
if
(
tileResolution
<
1.0
)
{
oss
<<
std
::
fixed
<<
std
::
setprecision
(
2
)
<<
tileResolution
;
}
else
{
oss
<<
static_cast
<
int32_t
>
(
rint
(
tileResolution
));
}
oss
<<
"-"
<<
tileY
<<
"-"
<<
tileX
<<
".jpg"
;
default:
default:
{};
{};
}
}
...
...
src/ui/map3D/Imagery.h
View file @
0b0b4757
...
@@ -43,8 +43,9 @@ public:
...
@@ -43,8 +43,9 @@ public:
enum
ImageryType
enum
ImageryType
{
{
MAP
=
0
,
GOOGLE_MAP
=
0
,
SATELLITE
=
1
GOOGLE_SATELLITE
=
1
,
SWISSTOPO_SATELLITE
=
2
};
};
void
setImageryType
(
ImageryType
type
);
void
setImageryType
(
ImageryType
type
);
...
@@ -100,7 +101,8 @@ private:
...
@@ -100,7 +101,8 @@ private:
void
UTMtoLL
(
double
utmNorthing
,
double
utmEasting
,
const
QString
&
utmZone
,
void
UTMtoLL
(
double
utmNorthing
,
double
utmEasting
,
const
QString
&
utmZone
,
double
&
latitude
,
double
&
longitude
)
const
;
double
&
latitude
,
double
&
longitude
)
const
;
QString
getTileURL
(
int32_t
tileX
,
int32_t
tileY
,
int32_t
zoomLevel
)
const
;
QString
getTileLocation
(
int32_t
tileX
,
int32_t
tileY
,
int32_t
zoomLevel
,
double
tileResolution
)
const
;
ImageryType
currentImageryType
;
ImageryType
currentImageryType
;
...
...
src/ui/map3D/Q3DWidget.cc
View file @
0b0b4757
...
@@ -232,7 +232,7 @@ Q3DWidget::userTimer(void)
...
@@ -232,7 +232,7 @@ Q3DWidget::userTimer(void)
{
{
if
(
timerFunc
)
if
(
timerFunc
)
{
{
timerFunc
(
timerFuncData
);
timerFunc
(
timerFuncData
);
}
}
}
}
...
@@ -356,7 +356,6 @@ Q3DWidget::getMouseY(void)
...
@@ -356,7 +356,6 @@ Q3DWidget::getMouseY(void)
return
mapFromGlobal
(
cursor
().
pos
()).
y
();
return
mapFromGlobal
(
cursor
().
pos
()).
y
();
}
}
void
void
Q3DWidget
::
rotateCamera
(
float
dx
,
float
dy
)
Q3DWidget
::
rotateCamera
(
float
dx
,
float
dy
)
{
{
...
@@ -858,9 +857,12 @@ Q3DWidget::timerEvent(QTimerEvent* event)
...
@@ -858,9 +857,12 @@ Q3DWidget::timerEvent(QTimerEvent* event)
}
}
void
void
Q3DWidget
::
closeEvent
(
QCloseEvent
*
)
Q3DWidget
::
closeEvent
(
QCloseEvent
*
event
)
{
{
// exit application
// exit application
timer
.
stop
();
event
->
accept
();
}
}
void
void
...
...
src/ui/map3D/QMap3DWidget.cc
View file @
0b0b4757
...
@@ -95,6 +95,7 @@ QMap3DWidget::buildLayout(void)
...
@@ -95,6 +95,7 @@ QMap3DWidget::buildLayout(void)
imageryComboBox
->
addItem
(
"None"
);
imageryComboBox
->
addItem
(
"None"
);
imageryComboBox
->
addItem
(
"Map (Google)"
);
imageryComboBox
->
addItem
(
"Map (Google)"
);
imageryComboBox
->
addItem
(
"Satellite (Google)"
);
imageryComboBox
->
addItem
(
"Satellite (Google)"
);
imageryComboBox
->
addItem
(
"Satellite (Swisstopo)"
);
QPushButton
*
recenterButton
=
new
QPushButton
(
this
);
QPushButton
*
recenterButton
=
new
QPushButton
(
this
);
recenterButton
->
setText
(
"Recenter Camera"
);
recenterButton
->
setText
(
"Recenter Camera"
);
...
@@ -536,11 +537,15 @@ QMap3DWidget::showImagery(const QString& text)
...
@@ -536,11 +537,15 @@ QMap3DWidget::showImagery(const QString& text)
{
{
if
(
text
.
compare
(
"Map (Google)"
)
==
0
)
if
(
text
.
compare
(
"Map (Google)"
)
==
0
)
{
{
imagery
->
setImageryType
(
Imagery
::
MAP
);
imagery
->
setImageryType
(
Imagery
::
GOOGLE_
MAP
);
}
}
else
if
(
text
.
compare
(
"Satellite (Google)"
)
==
0
)
else
if
(
text
.
compare
(
"Satellite (Google)"
)
==
0
)
{
{
imagery
->
setImageryType
(
Imagery
::
SATELLITE
);
imagery
->
setImageryType
(
Imagery
::
GOOGLE_SATELLITE
);
}
else
if
(
text
.
compare
(
"Satellite (Swisstopo)"
)
==
0
)
{
imagery
->
setImageryType
(
Imagery
::
SWISSTOPO_SATELLITE
);
}
}
displayImagery
=
true
;
displayImagery
=
true
;
}
}
...
@@ -682,6 +687,11 @@ QMap3DWidget::drawImagery(double originX, double originY, double originZ,
...
@@ -682,6 +687,11 @@ QMap3DWidget::drawImagery(double originX, double originY, double originZ,
{
{
minResolution
=
0.5
;
minResolution
=
0.5
;
}
}
else
if
(
imageryComboBox
->
currentText
().
compare
(
"Satellite (Swisstopo)"
)
==
0
)
{
minResolution
=
0.25
;
maxResolution
=
0.25
;
}
double
resolution
=
minResolution
;
double
resolution
=
minResolution
;
while
(
resolution
*
2.0
<
centerResolution
)
while
(
resolution
*
2.0
<
centerResolution
)
...
...
src/ui/map3D/WebImage.cc
View file @
0b0b4757
...
@@ -31,7 +31,6 @@ This file is part of the QGROUNDCONTROL project
...
@@ -31,7 +31,6 @@ This file is part of the QGROUNDCONTROL project
#include "WebImage.h"
#include "WebImage.h"
#include <QDebug>
#include <QGLWidget>
#include <QGLWidget>
WebImage
::
WebImage
()
WebImage
::
WebImage
()
...
@@ -83,7 +82,7 @@ WebImage::getData(void) const
...
@@ -83,7 +82,7 @@ WebImage::getData(void) const
return
image
->
scanLine
(
0
);
return
image
->
scanLine
(
0
);
}
}
void
bool
WebImage
::
setData
(
const
QByteArray
&
data
)
WebImage
::
setData
(
const
QByteArray
&
data
)
{
{
QImage
tempImage
;
QImage
tempImage
;
...
@@ -94,10 +93,32 @@ WebImage::setData(const QByteArray& data)
...
@@ -94,10 +93,32 @@ WebImage::setData(const QByteArray& data)
image
.
reset
(
new
QImage
);
image
.
reset
(
new
QImage
);
}
}
*
image
=
QGLWidget
::
convertToGLFormat
(
tempImage
);
*
image
=
QGLWidget
::
convertToGLFormat
(
tempImage
);
return
true
;
}
else
{
return
false
;
}
}
bool
WebImage
::
setData
(
const
QString
&
filename
)
{
QImage
tempImage
;
if
(
tempImage
.
load
(
filename
))
{
if
(
image
.
isNull
())
{
image
.
reset
(
new
QImage
);
}
*
image
=
QGLWidget
::
convertToGLFormat
(
tempImage
);
return
true
;
}
}
else
else
{
{
qDebug
()
<<
"# WARNING: cannot load image data for"
<<
sourceURL
;
return
false
;
}
}
}
}
...
...
src/ui/map3D/WebImage.h
View file @
0b0b4757
...
@@ -58,7 +58,8 @@ public:
...
@@ -58,7 +58,8 @@ public:
void
setSourceURL
(
const
QString
&
url
);
void
setSourceURL
(
const
QString
&
url
);
const
uint8_t
*
getData
(
void
)
const
;
const
uint8_t
*
getData
(
void
)
const
;
void
setData
(
const
QByteArray
&
data
);
bool
setData
(
const
QByteArray
&
data
);
bool
setData
(
const
QString
&
filename
);
int32_t
getWidth
(
void
)
const
;
int32_t
getWidth
(
void
)
const
;
int32_t
getHeight
(
void
)
const
;
int32_t
getHeight
(
void
)
const
;
...
...
src/ui/map3D/WebImageCache.cc
View file @
0b0b4757
...
@@ -104,7 +104,22 @@ WebImageCache::lookup(const QString& url)
...
@@ -104,7 +104,22 @@ WebImageCache::lookup(const QString& url)
++
currentReference
;
++
currentReference
;
cacheEntry
.
first
->
setState
(
WebImage
::
REQUESTED
);
cacheEntry
.
first
->
setState
(
WebImage
::
REQUESTED
);
networkManager
->
get
(
QNetworkRequest
(
QUrl
(
url
)));
if
(
url
.
left
(
4
).
compare
(
"http"
)
==
0
)
{
networkManager
->
get
(
QNetworkRequest
(
QUrl
(
url
)));
}
else
{
if
(
cacheEntry
.
first
->
setData
(
url
))
{
cacheEntry
.
first
->
setSyncFlag
(
true
);
cacheEntry
.
first
->
setState
(
WebImage
::
READY
);
}
else
{
cacheEntry
.
first
->
setState
(
WebImage
::
UNINITIALIZED
);
}
}
return
cacheEntry
;
return
cacheEntry
;
}
}
...
...
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