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
db075953
Commit
db075953
authored
Feb 25, 2012
by
LM
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'master' of github.com:mavlink/qgroundcontrol
parents
b302c815
9adfc8dc
Changes
25
Hide whitespace changes
Inline
Side-by-side
Showing
25 changed files
with
791 additions
and
319 deletions
+791
-319
qgroundcontrol.pro
qgroundcontrol.pro
+5
-3
GLOverlayGeode.cc
src/ui/map3D/GLOverlayGeode.cc
+8
-5
GlobalViewParams.cc
src/ui/map3D/GlobalViewParams.cc
+48
-12
GlobalViewParams.h
src/ui/map3D/GlobalViewParams.h
+19
-5
Imagery.cc
src/ui/map3D/Imagery.cc
+116
-67
Imagery.h
src/ui/map3D/Imagery.h
+12
-9
ImageryParamDialog.cc
src/ui/map3D/ImageryParamDialog.cc
+174
-0
ImageryParamDialog.h
src/ui/map3D/ImageryParamDialog.h
+36
-0
Pixhawk3DWidget.cc
src/ui/map3D/Pixhawk3DWidget.cc
+77
-23
Pixhawk3DWidget.h
src/ui/map3D/Pixhawk3DWidget.h
+4
-2
Q3DWidget.cc
src/ui/map3D/Q3DWidget.cc
+1
-1
SystemContainer.cc
src/ui/map3D/SystemContainer.cc
+6
-0
SystemContainer.h
src/ui/map3D/SystemContainer.h
+4
-0
TerrainParamDialog.cc
src/ui/map3D/TerrainParamDialog.cc
+26
-9
TerrainParamDialog.h
src/ui/map3D/TerrainParamDialog.h
+2
-0
Texture.cc
src/ui/map3D/Texture.cc
+62
-49
Texture.h
src/ui/map3D/Texture.h
+10
-9
TextureCache.cc
src/ui/map3D/TextureCache.cc
+29
-20
TextureCache.h
src/ui/map3D/TextureCache.h
+5
-5
ViewParamWidget.cc
src/ui/map3D/ViewParamWidget.cc
+15
-8
ViewParamWidget.h
src/ui/map3D/ViewParamWidget.h
+1
-0
WebImage.cc
src/ui/map3D/WebImage.cc
+41
-33
WebImage.h
src/ui/map3D/WebImage.h
+7
-7
WebImageCache.cc
src/ui/map3D/WebImageCache.cc
+75
-44
WebImageCache.h
src/ui/map3D/WebImageCache.h
+8
-8
No files found.
qgroundcontrol.pro
View file @
db075953
...
@@ -391,7 +391,8 @@ contains(DEPENDENCIES_PRESENT, osg) {
...
@@ -391,7 +391,8 @@ contains(DEPENDENCIES_PRESENT, osg) {
src
/
ui
/
map3D
/
Imagery
.
h
\
src
/
ui
/
map3D
/
Imagery
.
h
\
src
/
ui
/
map3D
/
HUDScaleGeode
.
h
\
src
/
ui
/
map3D
/
HUDScaleGeode
.
h
\
src
/
ui
/
map3D
/
WaypointGroupNode
.
h
\
src
/
ui
/
map3D
/
WaypointGroupNode
.
h
\
src
/
ui
/
map3D
/
TerrainParamDialog
.
h
src
/
ui
/
map3D
/
TerrainParamDialog
.
h
\
src
/
ui
/
map3D
/
ImageryParamDialog
.
h
}
}
contains
(
DEPENDENCIES_PRESENT
,
protobuf
)
:
contains
(
MAVLINK_CONF
,
pixhawk
)
{
contains
(
DEPENDENCIES_PRESENT
,
protobuf
)
:
contains
(
MAVLINK_CONF
,
pixhawk
)
{
message
(
"Including headers for Protocol Buffers"
)
message
(
"Including headers for Protocol Buffers"
)
...
@@ -535,7 +536,8 @@ contains(DEPENDENCIES_PRESENT, osg) {
...
@@ -535,7 +536,8 @@ contains(DEPENDENCIES_PRESENT, osg) {
src
/
ui
/
map3D
/
Imagery
.
cc
\
src
/
ui
/
map3D
/
Imagery
.
cc
\
src
/
ui
/
map3D
/
HUDScaleGeode
.
cc
\
src
/
ui
/
map3D
/
HUDScaleGeode
.
cc
\
src
/
ui
/
map3D
/
WaypointGroupNode
.
cc
\
src
/
ui
/
map3D
/
WaypointGroupNode
.
cc
\
src
/
ui
/
map3D
/
TerrainParamDialog
.
cc
src
/
ui
/
map3D
/
TerrainParamDialog
.
cc
\
src
/
ui
/
map3D
/
ImageryParamDialog
.
cc
contains
(
DEPENDENCIES_PRESENT
,
osgearth
)
{
contains
(
DEPENDENCIES_PRESENT
,
osgearth
)
{
message
(
"Including sources for osgEarth"
)
message
(
"Including sources for osgEarth"
)
...
@@ -602,4 +604,4 @@ win32-msvc2008|win32-msvc2010|linux {
...
@@ -602,4 +604,4 @@ win32-msvc2008|win32-msvc2010|linux {
#
TO
DO
:
build
library
when
it
does
not
exist
already
#
TO
DO
:
build
library
when
it
does
not
exist
already
LIBS
+=
-
LthirdParty
/
libxbee
/
lib
\
LIBS
+=
-
LthirdParty
/
libxbee
/
lib
\
-
llibxbee
-
llibxbee
}
}
\ No newline at end of file
src/ui/map3D/GLOverlayGeode.cc
View file @
db075953
...
@@ -36,14 +36,16 @@ GLOverlayGeode::messageTimestamp(void) const
...
@@ -36,14 +36,16 @@ GLOverlayGeode::messageTimestamp(void) const
GLOverlayGeode
::
GLOverlayDrawable
::
GLOverlayDrawable
()
GLOverlayGeode
::
GLOverlayDrawable
::
GLOverlayDrawable
()
{
{
setUseDisplayList
(
true
);
setUseDisplayList
(
false
);
setUseVertexBufferObjects
(
true
);
}
}
GLOverlayGeode
::
GLOverlayDrawable
::
GLOverlayDrawable
(
const
GLOverlayDrawable
&
drawable
,
GLOverlayGeode
::
GLOverlayDrawable
::
GLOverlayDrawable
(
const
GLOverlayDrawable
&
drawable
,
const
osg
::
CopyOp
&
copyop
)
const
osg
::
CopyOp
&
copyop
)
:
osg
::
Drawable
(
drawable
,
copyop
)
:
osg
::
Drawable
(
drawable
,
copyop
)
{
{
setUseDisplayList
(
true
);
setUseDisplayList
(
false
);
setUseVertexBufferObjects
(
true
);
}
}
void
void
...
@@ -136,8 +138,6 @@ GLOverlayGeode::GLOverlayDrawable::setOverlay(px::GLOverlay &overlay)
...
@@ -136,8 +138,6 @@ GLOverlayGeode::GLOverlayDrawable::setOverlay(px::GLOverlay &overlay)
break
;
break
;
}
}
}
}
dirtyDisplayList
();
}
}
void
void
...
@@ -148,9 +148,11 @@ GLOverlayGeode::GLOverlayDrawable::drawImplementation(osg::RenderInfo&) const
...
@@ -148,9 +148,11 @@ GLOverlayGeode::GLOverlayDrawable::drawImplementation(osg::RenderInfo&) const
return
;
return
;
}
}
glMatrixMode
(
GL_MODELVIEW
);
glDisable
(
GL_LIGHTING
);
glPushMatrix
();
glPushMatrix
();
glScalef
(
-
1.0
f
,
1.0
f
,
1.0
f
);
glScalef
(
-
1.0
f
,
1.0
f
,
-
1.0
f
);
glRotatef
(
90.0
f
,
0.0
f
,
0.0
f
,
1.0
f
);
glRotatef
(
90.0
f
,
0.0
f
,
0.0
f
,
1.0
f
);
const
std
::
string
&
data
=
mOverlay
.
data
();
const
std
::
string
&
data
=
mOverlay
.
data
();
...
@@ -401,6 +403,7 @@ GLOverlayGeode::GLOverlayDrawable::drawImplementation(osg::RenderInfo&) const
...
@@ -401,6 +403,7 @@ GLOverlayGeode::GLOverlayDrawable::drawImplementation(osg::RenderInfo&) const
}
}
glPopMatrix
();
glPopMatrix
();
glEnable
(
GL_LIGHTING
);
}
}
osg
::
BoundingBox
osg
::
BoundingBox
...
...
src/ui/map3D/GlobalViewParams.cc
View file @
db075953
...
@@ -36,6 +36,30 @@ GlobalViewParams::displayWorldGrid(void) const
...
@@ -36,6 +36,30 @@ GlobalViewParams::displayWorldGrid(void) const
return
mDisplayWorldGrid
;
return
mDisplayWorldGrid
;
}
}
QVector3D
&
GlobalViewParams
::
imageryOffset
(
void
)
{
return
mImageryOffset
;
}
QVector3D
GlobalViewParams
::
imageryOffset
(
void
)
const
{
return
mImageryOffset
;
}
QString
&
GlobalViewParams
::
imageryPath
(
void
)
{
return
mImageryPath
;
}
QString
GlobalViewParams
::
imageryPath
(
void
)
const
{
return
mImageryPath
;
}
Imagery
::
Type
&
Imagery
::
Type
&
GlobalViewParams
::
imageryType
(
void
)
GlobalViewParams
::
imageryType
(
void
)
{
{
...
@@ -72,16 +96,34 @@ GlobalViewParams::frame(void) const
...
@@ -72,16 +96,34 @@ GlobalViewParams::frame(void) const
return
mFrame
;
return
mFrame
;
}
}
QVector4D
&
void
GlobalViewParams
::
terrainOffset
(
void
)
GlobalViewParams
::
signalImageryParamsChanged
(
void
)
{
emit
imageryParamsChanged
();
}
QVector3D
&
GlobalViewParams
::
terrainPositionOffset
(
void
)
{
{
return
mTerrainOffset
;
return
mTerrain
Position
Offset
;
}
}
QVector
4
D
QVector
3
D
GlobalViewParams
::
terrainOffset
(
void
)
const
GlobalViewParams
::
terrain
Position
Offset
(
void
)
const
{
{
return
mTerrainOffset
;
return
mTerrainPositionOffset
;
}
QVector3D
&
GlobalViewParams
::
terrainAttitudeOffset
(
void
)
{
return
mTerrainAttitudeOffset
;
}
QVector3D
GlobalViewParams
::
terrainAttitudeOffset
(
void
)
const
{
return
mTerrainAttitudeOffset
;
}
}
void
void
...
@@ -120,12 +162,6 @@ GlobalViewParams::frameChanged(const QString& text)
...
@@ -120,12 +162,6 @@ GlobalViewParams::frameChanged(const QString& text)
}
}
}
}
void
GlobalViewParams
::
imageryTypeChanged
(
int
index
)
{
mImageryType
=
static_cast
<
Imagery
::
Type
>
(
index
);
}
void
void
GlobalViewParams
::
toggleWorldGrid
(
int
state
)
GlobalViewParams
::
toggleWorldGrid
(
int
state
)
{
{
...
...
src/ui/map3D/GlobalViewParams.h
View file @
db075953
...
@@ -3,7 +3,7 @@
...
@@ -3,7 +3,7 @@
#include <QObject>
#include <QObject>
#include <QString>
#include <QString>
#include <QVector
4
D>
#include <QVector
3
D>
#include "QGCMAVLink.h"
#include "QGCMAVLink.h"
#include "Imagery.h"
#include "Imagery.h"
...
@@ -21,6 +21,12 @@ public:
...
@@ -21,6 +21,12 @@ public:
bool
&
displayWorldGrid
(
void
);
bool
&
displayWorldGrid
(
void
);
bool
displayWorldGrid
(
void
)
const
;
bool
displayWorldGrid
(
void
)
const
;
QVector3D
&
imageryOffset
(
void
);
QVector3D
imageryOffset
(
void
)
const
;
QString
&
imageryPath
(
void
);
QString
imageryPath
(
void
)
const
;
Imagery
::
Type
&
imageryType
(
void
);
Imagery
::
Type
&
imageryType
(
void
);
Imagery
::
Type
imageryType
(
void
)
const
;
Imagery
::
Type
imageryType
(
void
)
const
;
...
@@ -30,26 +36,34 @@ public:
...
@@ -30,26 +36,34 @@ public:
MAV_FRAME
&
frame
(
void
);
MAV_FRAME
&
frame
(
void
);
MAV_FRAME
frame
(
void
)
const
;
MAV_FRAME
frame
(
void
)
const
;
QVector4D
&
terrainOffset
(
void
);
void
signalImageryParamsChanged
(
void
);
QVector4D
terrainOffset
(
void
)
const
;
QVector3D
&
terrainPositionOffset
(
void
);
QVector3D
terrainPositionOffset
(
void
)
const
;
QVector3D
&
terrainAttitudeOffset
(
void
);
QVector3D
terrainAttitudeOffset
(
void
)
const
;
public
slots
:
public
slots
:
void
followCameraChanged
(
const
QString
&
text
);
void
followCameraChanged
(
const
QString
&
text
);
void
frameChanged
(
const
QString
&
text
);
void
frameChanged
(
const
QString
&
text
);
void
imageryTypeChanged
(
int
index
);
void
toggleTerrain
(
int
state
);
void
toggleTerrain
(
int
state
);
void
toggleWorldGrid
(
int
state
);
void
toggleWorldGrid
(
int
state
);
signals:
signals:
void
followCameraChanged
(
int
systemId
);
void
followCameraChanged
(
int
systemId
);
void
imageryParamsChanged
(
void
);
private:
private:
bool
mDisplayTerrain
;
bool
mDisplayTerrain
;
bool
mDisplayWorldGrid
;
bool
mDisplayWorldGrid
;
QVector3D
mImageryOffset
;
QString
mImageryPath
;
Imagery
::
Type
mImageryType
;
Imagery
::
Type
mImageryType
;
int
mFollowCameraId
;
int
mFollowCameraId
;
MAV_FRAME
mFrame
;
MAV_FRAME
mFrame
;
QVector4D
mTerrainOffset
;
QVector3D
mTerrainPositionOffset
;
QVector3D
mTerrainAttitudeOffset
;
};
};
typedef
QSharedPointer
<
GlobalViewParams
>
GlobalViewParamsPtr
;
typedef
QSharedPointer
<
GlobalViewParams
>
GlobalViewParamsPtr
;
...
...
src/ui/map3D/Imagery.cc
View file @
db075953
...
@@ -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 <cstdio>
#include <iomanip>
#include <iomanip>
#include <sstream>
#include <sstream>
...
@@ -41,28 +42,39 @@ const double WGS84_ECCSQ = 0.00669437999013;
...
@@ -41,28 +42,39 @@ const double WGS84_ECCSQ = 0.00669437999013;
const
int
MAX_ZOOM_LEVEL
=
20
;
const
int
MAX_ZOOM_LEVEL
=
20
;
Imagery
::
Imagery
()
Imagery
::
Imagery
()
:
textureCache
(
new
TextureCache
(
1000
))
:
mTextureCache
(
new
TextureCache
(
1000
))
,
mImageryType
(
Imagery
::
BLANK_MAP
)
,
mXOffset
(
0.0
)
,
mYOffset
(
0.0
)
,
mZOffset
(
0.0
)
{
{
setCullingActive
(
false
);
}
}
Imagery
::
Type
Imagery
::
Type
Imagery
::
getImageryType
(
void
)
const
Imagery
::
getImageryType
(
void
)
const
{
{
return
current
ImageryType
;
return
m
ImageryType
;
}
}
void
void
Imagery
::
setImageryType
(
Imagery
::
Type
type
)
Imagery
::
setImageryType
(
Imagery
::
Type
type
)
{
{
currentImageryType
=
type
;
mImageryType
=
type
;
}
void
Imagery
::
setOffset
(
double
xOffset
,
double
yOffset
,
double
zOffset
)
{
mXOffset
=
xOffset
;
mYOffset
=
yOffset
;
mZOffset
=
zOffset
;
}
}
void
void
Imagery
::
set
Offset
(
double
xOffset
,
double
yOffset
)
Imagery
::
set
Path
(
const
QString
&
path
)
{
{
this
->
xOffset
=
xOffset
;
mImageryPath
=
path
.
toStdString
();
this
->
yOffset
=
yOffset
;
}
}
void
void
...
@@ -70,21 +82,27 @@ Imagery::prefetch2D(double windowWidth, double windowHeight,
...
@@ -70,21 +82,27 @@ Imagery::prefetch2D(double windowWidth, double windowHeight,
double
zoom
,
double
xOrigin
,
double
yOrigin
,
double
zoom
,
double
xOrigin
,
double
yOrigin
,
const
QString
&
utmZone
)
const
QString
&
utmZone
)
{
{
if
(
currentImageryType
==
BLANK_MAP
)
{
if
(
mImageryType
==
BLANK_MAP
)
{
return
;
return
;
}
}
double
tileResolution
=
1.0
;
double
tileResolution
=
1.0
;
if
(
currentImageryType
==
GOOGLE_SATELLITE
||
if
(
mImageryType
==
GOOGLE_SATELLITE
||
currentImageryType
==
GOOGLE_MAP
)
{
mImageryType
==
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
)
{
tileResolution
*=
2.0
;
tileResolution
*=
2.0
;
}
}
if
(
tileResolution
>
512.0
)
{
if
(
tileResolution
>
512.0
)
{
tileResolution
=
512.0
;
tileResolution
=
512.0
;
}
}
}
else
if
(
currentImageryType
==
SWISSTOPO_SATELLITE
)
{
}
else
if
(
mImageryType
==
OFFLINE_SATELLITE
)
{
tileResolution
=
0.25
;
tileResolution
=
0.25
;
}
}
...
@@ -98,11 +116,13 @@ Imagery::prefetch2D(double windowWidth, double windowHeight,
...
@@ -98,11 +116,13 @@ Imagery::prefetch2D(double windowWidth, double windowHeight,
yOrigin
+
windowHeight
/
2.0
/
zoom
*
1.5
,
utmZone
,
yOrigin
+
windowHeight
/
2.0
/
zoom
*
1.5
,
utmZone
,
minTileX
,
minTileY
,
maxTileX
,
maxTileY
,
zoomLevel
);
minTileX
,
minTileY
,
maxTileX
,
maxTileY
,
zoomLevel
);
for
(
int
r
=
minTileY
;
r
<=
maxTileY
;
++
r
)
{
for
(
int
r
=
minTileY
;
r
<=
maxTileY
;
++
r
)
for
(
int
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
{
for
(
int
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
QString
url
=
getTileLocation
(
c
,
r
,
zoomLevel
,
tileResolution
);
QString
url
=
getTileLocation
(
c
,
r
,
zoomLevel
,
tileResolution
);
TexturePtr
t
=
t
extureCache
->
get
(
url
);
TexturePtr
t
=
mT
extureCache
->
get
(
url
);
}
}
}
}
}
}
...
@@ -110,28 +130,34 @@ Imagery::prefetch2D(double windowWidth, double windowHeight,
...
@@ -110,28 +130,34 @@ Imagery::prefetch2D(double windowWidth, double windowHeight,
void
void
Imagery
::
draw2D
(
double
windowWidth
,
double
windowHeight
,
Imagery
::
draw2D
(
double
windowWidth
,
double
windowHeight
,
double
zoom
,
double
xOrigin
,
double
yOrigin
,
double
zoom
,
double
xOrigin
,
double
yOrigin
,
double
xOffset
,
double
yOffset
,
double
zOffset
,
const
QString
&
utmZone
)
const
QString
&
utmZone
)
{
{
if
(
getNumDrawables
()
>
0
)
{
if
(
getNumDrawables
()
>
0
)
{
removeDrawables
(
0
,
getNumDrawables
());
removeDrawables
(
0
,
getNumDrawables
());
}
}
if
(
currentImageryType
==
BLANK_MAP
)
{
if
(
mImageryType
==
BLANK_MAP
)
{
return
;
return
;
}
}
double
tileResolution
=
1.0
;
double
tileResolution
=
1.0
;
if
(
currentImageryType
==
GOOGLE_SATELLITE
||
if
(
mImageryType
==
GOOGLE_SATELLITE
||
currentImageryType
==
GOOGLE_MAP
)
{
mImageryType
==
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
)
{
tileResolution
*=
2.0
;
tileResolution
*=
2.0
;
}
}
if
(
tileResolution
>
512.0
)
{
if
(
tileResolution
>
512.0
)
{
tileResolution
=
512.0
;
tileResolution
=
512.0
;
}
}
}
else
if
(
currentImageryType
==
SWISSTOPO_SATELLITE
)
{
}
else
if
(
mImageryType
==
OFFLINE_SATELLITE
)
{
tileResolution
=
0.25
;
tileResolution
=
0.25
;
}
}
...
@@ -145,20 +171,23 @@ Imagery::draw2D(double windowWidth, double windowHeight,
...
@@ -145,20 +171,23 @@ Imagery::draw2D(double windowWidth, double windowHeight,
yOrigin
+
windowHeight
/
2.0
/
zoom
*
1.5
,
utmZone
,
yOrigin
+
windowHeight
/
2.0
/
zoom
*
1.5
,
utmZone
,
minTileX
,
minTileY
,
maxTileX
,
maxTileY
,
zoomLevel
);
minTileX
,
minTileY
,
maxTileX
,
maxTileY
,
zoomLevel
);
for
(
int
r
=
minTileY
;
r
<=
maxTileY
;
++
r
)
{
for
(
int
r
=
minTileY
;
r
<=
maxTileY
;
++
r
)
for
(
int
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
{
for
(
int
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
QString
tileURL
=
getTileLocation
(
c
,
r
,
zoomLevel
,
tileResolution
);
QString
tileURL
=
getTileLocation
(
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
);
TexturePtr
t
=
textureCache
->
get
(
tileURL
);
TexturePtr
t
=
mTextureCache
->
get
(
tileURL
);
if
(
!
t
.
isNull
())
{
if
(
!
t
.
isNull
())
addDrawable
(
t
->
draw
(
y1
-
yOffset
,
x1
-
xOffset
,
{
y2
-
yOffset
,
x2
-
xOffset
,
addDrawable
(
t
->
draw
(
y1
,
x1
,
y3
-
yOffset
,
x3
-
xOffset
,
y2
,
x2
,
y4
-
yOffset
,
x4
-
xOffset
,
y3
,
x3
,
zOffset
,
y4
,
x4
,
-
mZOffset
,
true
));
true
));
}
}
}
}
...
@@ -170,7 +199,8 @@ Imagery::prefetch3D(double radius, double tileResolution,
...
@@ -170,7 +199,8 @@ Imagery::prefetch3D(double radius, double tileResolution,
double
xOrigin
,
double
yOrigin
,
double
xOrigin
,
double
yOrigin
,
const
QString
&
utmZone
)
const
QString
&
utmZone
)
{
{
if
(
currentImageryType
==
BLANK_MAP
)
{
if
(
mImageryType
==
BLANK_MAP
)
{
return
;
return
;
}
}
...
@@ -178,15 +208,17 @@ Imagery::prefetch3D(double radius, double tileResolution,
...
@@ -178,15 +208,17 @@ Imagery::prefetch3D(double radius, double tileResolution,
int
zoomLevel
;
int
zoomLevel
;
tileBounds
(
tileResolution
,
tileBounds
(
tileResolution
,
xOrigin
-
radius
,
yOrigin
-
radius
,
xOrigin
+
mXOffset
-
radius
,
yOrigin
+
mYOffset
-
radius
,
xOrigin
+
radius
,
yOrigin
+
radius
,
utmZone
,
xOrigin
+
mXOffset
+
radius
,
yOrigin
+
mYOffset
+
radius
,
utmZone
,
minTileX
,
minTileY
,
maxTileX
,
maxTileY
,
zoomLevel
);
minTileX
,
minTileY
,
maxTileX
,
maxTileY
,
zoomLevel
);
for
(
int
r
=
minTileY
;
r
<=
maxTileY
;
++
r
)
{
for
(
int
r
=
minTileY
;
r
<=
maxTileY
;
++
r
)
for
(
int
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
{
for
(
int
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
QString
url
=
getTileLocation
(
c
,
r
,
zoomLevel
,
tileResolution
);
QString
url
=
getTileLocation
(
c
,
r
,
zoomLevel
,
tileResolution
);
TexturePtr
t
=
t
extureCache
->
get
(
url
);
TexturePtr
t
=
mT
extureCache
->
get
(
url
);
}
}
}
}
}
}
...
@@ -194,14 +226,16 @@ Imagery::prefetch3D(double radius, double tileResolution,
...
@@ -194,14 +226,16 @@ Imagery::prefetch3D(double radius, double tileResolution,
void
void
Imagery
::
draw3D
(
double
radius
,
double
tileResolution
,
Imagery
::
draw3D
(
double
radius
,
double
tileResolution
,
double
xOrigin
,
double
yOrigin
,
double
xOrigin
,
double
yOrigin
,
double
xOffset
,
double
yOffset
,
double
zOffset
,
double
xOffset
,
double
yOffset
,
const
QString
&
utmZone
)
const
QString
&
utmZone
)
{
{
if
(
getNumDrawables
()
>
0
)
{
if
(
getNumDrawables
()
>
0
)
{
removeDrawables
(
0
,
getNumDrawables
());
removeDrawables
(
0
,
getNumDrawables
());
}
}
if
(
currentImageryType
==
BLANK_MAP
)
{
if
(
mImageryType
==
BLANK_MAP
)
{
return
;
return
;
}
}
...
@@ -209,25 +243,28 @@ Imagery::draw3D(double radius, double tileResolution,
...
@@ -209,25 +243,28 @@ Imagery::draw3D(double radius, double tileResolution,
int
zoomLevel
;
int
zoomLevel
;
tileBounds
(
tileResolution
,
tileBounds
(
tileResolution
,
xOrigin
-
radius
,
yOrigin
-
radius
,
xOrigin
+
mXOffset
-
radius
,
yOrigin
+
mYOffset
-
radius
,
xOrigin
+
radius
,
yOrigin
+
radius
,
utmZone
,
xOrigin
+
mXOffset
+
radius
,
yOrigin
+
mYOffset
+
radius
,
utmZone
,
minTileX
,
minTileY
,
maxTileX
,
maxTileY
,
zoomLevel
);
minTileX
,
minTileY
,
maxTileX
,
maxTileY
,
zoomLevel
);
for
(
int
r
=
minTileY
;
r
<=
maxTileY
;
++
r
)
{
for
(
int
r
=
minTileY
;
r
<=
maxTileY
;
++
r
)
for
(
int
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
{
for
(
int
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
QString
tileURL
=
getTileLocation
(
c
,
r
,
zoomLevel
,
tileResolution
);
QString
tileURL
=
getTileLocation
(
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
);
TexturePtr
t
=
t
extureCache
->
get
(
tileURL
);
TexturePtr
t
=
mT
extureCache
->
get
(
tileURL
);
if
(
!
t
.
isNull
())
{
if
(
!
t
.
isNull
())
addDrawable
(
t
->
draw
(
y1
-
yOffset
,
x1
-
xOffset
,
{
y2
-
yOffset
,
x2
-
xOffset
,
addDrawable
(
t
->
draw
(
y1
-
mYOffset
+
yOffset
,
x1
-
mXOffset
+
xOffset
,
y3
-
yOffset
,
x3
-
xOffset
,
y2
-
mYOffset
+
yOffset
,
x2
-
mXOffset
+
xOffset
,
y4
-
yOffset
,
x4
-
xOffset
,
y3
-
mYOffset
+
yOffset
,
x3
-
mXOffset
+
xOffset
,
zOffset
,
y4
-
mYOffset
+
yOffset
,
x4
-
mXOffset
+
xOffset
,
-
mZOffset
,
true
));
true
));
}
}
}
}
...
@@ -237,7 +274,7 @@ Imagery::draw3D(double radius, double tileResolution,
...
@@ -237,7 +274,7 @@ Imagery::draw3D(double radius, double tileResolution,
bool
bool
Imagery
::
update
(
void
)
Imagery
::
update
(
void
)
{
{
t
extureCache
->
sync
();
mT
extureCache
->
sync
();
return
true
;
return
true
;
}
}
...
@@ -247,8 +284,9 @@ Imagery::imageBounds(int tileX, int tileY, double tileResolution,
...
@@ -247,8 +284,9 @@ Imagery::imageBounds(int tileX, int 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
{
{
if
(
currentImageryType
==
GOOGLE_MAP
||
if
(
mImageryType
==
GOOGLE_MAP
||
currentImageryType
==
GOOGLE_SATELLITE
)
{
mImageryType
==
GOOGLE_SATELLITE
)
{
int
zoomLevel
=
MAX_ZOOM_LEVEL
-
static_cast
<
int
>
(
rint
(
log2
(
tileResolution
)));
int
zoomLevel
=
MAX_ZOOM_LEVEL
-
static_cast
<
int
>
(
rint
(
log2
(
tileResolution
)));
int
numTiles
=
static_cast
<
int
>
(
exp2
(
static_cast
<
double
>
(
zoomLevel
)));
int
numTiles
=
static_cast
<
int
>
(
exp2
(
static_cast
<
double
>
(
zoomLevel
)));
...
@@ -263,7 +301,9 @@ Imagery::imageBounds(int tileX, int tileY, double tileResolution,
...
@@ -263,7 +301,9 @@ Imagery::imageBounds(int tileX, int tileY, double tileResolution,
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
)
{
}
else
if
(
mImageryType
==
OFFLINE_SATELLITE
)
{
double
utmMultiplier
=
tileResolution
*
200.0
;
double
utmMultiplier
=
tileResolution
*
200.0
;
double
minX
=
tileX
*
utmMultiplier
;
double
minX
=
tileX
*
utmMultiplier
;
double
maxX
=
minX
+
utmMultiplier
;
double
maxX
=
minX
+
utmMultiplier
;
...
@@ -293,15 +333,18 @@ Imagery::tileBounds(double tileResolution,
...
@@ -293,15 +333,18 @@ Imagery::tileBounds(double tileResolution,
double
centerUtmY
=
(
maxUtmY
-
minUtmY
)
/
2.0
+
minUtmY
;
double
centerUtmY
=
(
maxUtmY
-
minUtmY
)
/
2.0
+
minUtmY
;
int
centerTileX
,
centerTileY
;
int
centerTileX
,
centerTileY
;
if
(
currentImageryType
==
GOOGLE_MAP
||
if
(
mImageryType
==
GOOGLE_MAP
||
currentImageryType
==
GOOGLE_SATELLITE
)
{
mImageryType
==
GOOGLE_SATELLITE
)
{
UTMtoTile
(
minUtmX
,
minUtmY
,
utmZone
,
tileResolution
,
UTMtoTile
(
minUtmX
,
minUtmY
,
utmZone
,
tileResolution
,
minTileX
,
maxTileY
,
zoomLevel
);
minTileX
,
maxTileY
,
zoomLevel
);
UTMtoTile
(
centerUtmX
,
centerUtmY
,
utmZone
,
tileResolution
,
UTMtoTile
(
centerUtmX
,
centerUtmY
,
utmZone
,
tileResolution
,
centerTileX
,
centerTileY
,
zoomLevel
);
centerTileX
,
centerTileY
,
zoomLevel
);
UTMtoTile
(
maxUtmX
,
maxUtmY
,
utmZone
,
tileResolution
,
UTMtoTile
(
maxUtmX
,
maxUtmY
,
utmZone
,
tileResolution
,
maxTileX
,
minTileY
,
zoomLevel
);
maxTileX
,
minTileY
,
zoomLevel
);
}
else
if
(
currentImageryType
==
SWISSTOPO_SATELLITE
)
{
}
else
if
(
mImageryType
==
OFFLINE_SATELLITE
)
{
double
utmMultiplier
=
tileResolution
*
200
;
double
utmMultiplier
=
tileResolution
*
200
;
minTileX
=
static_cast
<
int
>
(
rint
(
minUtmX
/
utmMultiplier
));
minTileX
=
static_cast
<
int
>
(
rint
(
minUtmX
/
utmMultiplier
));
...
@@ -312,11 +355,13 @@ Imagery::tileBounds(double tileResolution,
...
@@ -312,11 +355,13 @@ Imagery::tileBounds(double tileResolution,
maxTileY
=
static_cast
<
int
>
(
rint
(
maxUtmY
/
utmMultiplier
));
maxTileY
=
static_cast
<
int
>
(
rint
(
maxUtmY
/
utmMultiplier
));
}
}
if
(
maxTileX
-
minTileX
+
1
>
14
)
{
if
(
maxTileX
-
minTileX
+
1
>
14
)
{
minTileX
=
centerTileX
-
7
;
minTileX
=
centerTileX
-
7
;
maxTileX
=
centerTileX
+
6
;
maxTileX
=
centerTileX
+
6
;
}
}
if
(
maxTileY
-
minTileY
+
1
>
14
)
{
if
(
maxTileY
-
minTileY
+
1
>
14
)
{
minTileY
=
centerTileY
-
7
;
minTileY
=
centerTileY
-
7
;
maxTileY
=
centerTileY
+
6
;
maxTileY
=
centerTileY
+
6
;
}
}
...
@@ -558,7 +603,8 @@ Imagery::getTileLocation(int tileX, int tileY, int zoomLevel,
...
@@ -558,7 +603,8 @@ Imagery::getTileLocation(int tileX, int tileY, int zoomLevel,
{
{
std
::
ostringstream
oss
;
std
::
ostringstream
oss
;
switch
(
currentImageryType
)
{
switch
(
mImageryType
)
{
case
GOOGLE_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
;
...
@@ -567,12 +613,15 @@ Imagery::getTileLocation(int tileX, int tileY, int zoomLevel,
...
@@ -567,12 +613,15 @@ Imagery::getTileLocation(int tileX, int tileY, int zoomLevel,
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
:
case
OFFLINE
_SATELLITE
:
oss
<<
"../map/eth_zurich_swissimage_025
/200/color/"
<<
tileY
oss
<<
mImageryPath
<<
"
/200/color/"
<<
tileY
<<
"/tile-"
;
<<
"/tile-"
;
if
(
tileResolution
<
1.0
)
{
if
(
tileResolution
<
1.0
)
{
oss
<<
std
::
fixed
<<
std
::
setprecision
(
2
)
<<
tileResolution
;
oss
<<
std
::
fixed
<<
std
::
setprecision
(
2
)
<<
tileResolution
;
}
else
{
}
else
{
oss
<<
static_cast
<
int
>
(
rint
(
tileResolution
));
oss
<<
static_cast
<
int
>
(
rint
(
tileResolution
));
}
}
oss
<<
"-"
<<
tileY
<<
"-"
<<
tileX
<<
".jpg"
;
oss
<<
"-"
<<
tileY
<<
"-"
<<
tileX
<<
".jpg"
;
...
...
src/ui/map3D/Imagery.h
View file @
db075953
...
@@ -41,25 +41,26 @@ This file is part of the QGROUNDCONTROL project
...
@@ -41,25 +41,26 @@ This file is part of the QGROUNDCONTROL project
class
Imagery
:
public
osg
::
Geode
class
Imagery
:
public
osg
::
Geode
{
{
public:
public:
enum
Type
{
enum
Type
{
BLANK_MAP
=
0
,
BLANK_MAP
=
0
,
GOOGLE_MAP
=
1
,
GOOGLE_MAP
=
1
,
GOOGLE_SATELLITE
=
2
,
GOOGLE_SATELLITE
=
2
,
SWISSTOPO
_SATELLITE
=
3
OFFLINE
_SATELLITE
=
3
};
};
Imagery
();
Imagery
();
Type
getImageryType
(
void
)
const
;
Type
getImageryType
(
void
)
const
;
void
setImageryType
(
Type
type
);
void
setImageryType
(
Type
type
);
void
setOffset
(
double
xOffset
,
double
yOffset
);
void
setOffset
(
double
xOffset
,
double
yOffset
,
double
zOffset
=
0
.
0
);
void
setPath
(
const
QString
&
path
);
void
prefetch2D
(
double
windowWidth
,
double
windowHeight
,
void
prefetch2D
(
double
windowWidth
,
double
windowHeight
,
double
zoom
,
double
xOrigin
,
double
yOrigin
,
double
zoom
,
double
xOrigin
,
double
yOrigin
,
const
QString
&
utmZone
);
const
QString
&
utmZone
);
void
draw2D
(
double
windowWidth
,
double
windowHeight
,
void
draw2D
(
double
windowWidth
,
double
windowHeight
,
double
zoom
,
double
xOrigin
,
double
yOrigin
,
double
zoom
,
double
xOrigin
,
double
yOrigin
,
double
xOffset
,
double
yOffset
,
double
zOffset
,
const
QString
&
utmZone
);
const
QString
&
utmZone
);
void
prefetch3D
(
double
radius
,
double
tileResolution
,
void
prefetch3D
(
double
radius
,
double
tileResolution
,
...
@@ -67,7 +68,7 @@ public:
...
@@ -67,7 +68,7 @@ public:
const
QString
&
utmZone
);
const
QString
&
utmZone
);
void
draw3D
(
double
radius
,
double
tileResolution
,
void
draw3D
(
double
radius
,
double
tileResolution
,
double
xOrigin
,
double
yOrigin
,
double
xOrigin
,
double
yOrigin
,
double
xOffset
,
double
yOffset
,
double
zOffset
,
double
xOffset
,
double
yOffset
,
const
QString
&
utmZone
);
const
QString
&
utmZone
);
bool
update
(
void
);
bool
update
(
void
);
...
@@ -102,12 +103,14 @@ private:
...
@@ -102,12 +103,14 @@ private:
QString
getTileLocation
(
int
tileX
,
int
tileY
,
int
zoomLevel
,
QString
getTileLocation
(
int
tileX
,
int
tileY
,
int
zoomLevel
,
double
tileResolution
)
const
;
double
tileResolution
)
const
;
QScopedPointer
<
TextureCache
>
t
extureCache
;
QScopedPointer
<
TextureCache
>
mT
extureCache
;
Type
currentImageryType
;
Type
mImageryType
;
std
::
string
mImageryPath
;
double
xOffset
;
double
mXOffset
;
double
yOffset
;
double
mYOffset
;
double
mZOffset
;
};
};
#endif // IMAGERY_H
#endif // IMAGERY_H
src/ui/map3D/ImageryParamDialog.cc
0 → 100644
View file @
db075953
#include "ImageryParamDialog.h"
#include <QDesktopServices>
#include <QFileDialog>
#include <QFormLayout>
#include <QGroupBox>
#include <QPushButton>
ImageryParamDialog
::
ImageryParamDialog
(
QWidget
*
parent
)
:
QDialog
(
parent
)
{
QVBoxLayout
*
layout
=
new
QVBoxLayout
;
setLayout
(
layout
);
setWindowTitle
(
tr
(
"Imagery Parameters"
));
setModal
(
true
);
buildLayout
(
layout
);
}
void
ImageryParamDialog
::
getImageryParams
(
GlobalViewParamsPtr
&
globalViewParams
)
{
ImageryParamDialog
dialog
;
switch
(
globalViewParams
->
imageryType
())
{
case
Imagery
:
:
BLANK_MAP
:
dialog
.
mImageryTypeComboBox
->
setCurrentIndex
(
0
);
break
;
case
Imagery
:
:
GOOGLE_MAP
:
dialog
.
mImageryTypeComboBox
->
setCurrentIndex
(
1
);
break
;
case
Imagery
:
:
GOOGLE_SATELLITE
:
dialog
.
mImageryTypeComboBox
->
setCurrentIndex
(
2
);
break
;
case
Imagery
:
:
OFFLINE_SATELLITE
:
dialog
.
mImageryTypeComboBox
->
setCurrentIndex
(
3
);
break
;
}
dialog
.
mPathLineEdit
->
setText
(
globalViewParams
->
imageryPath
());
QVector3D
&
imageryOffset
=
globalViewParams
->
imageryOffset
();
dialog
.
mXOffsetSpinBox
->
setValue
(
imageryOffset
.
x
());
dialog
.
mYOffsetSpinBox
->
setValue
(
imageryOffset
.
y
());
dialog
.
mZOffsetSpinBox
->
setValue
(
imageryOffset
.
z
());
if
(
dialog
.
exec
()
==
QDialog
::
Accepted
)
{
switch
(
dialog
.
mImageryTypeComboBox
->
currentIndex
())
{
case
0
:
globalViewParams
->
imageryType
()
=
Imagery
::
BLANK_MAP
;
break
;
case
1
:
globalViewParams
->
imageryType
()
=
Imagery
::
GOOGLE_MAP
;
break
;
case
2
:
globalViewParams
->
imageryType
()
=
Imagery
::
GOOGLE_SATELLITE
;
break
;
case
3
:
globalViewParams
->
imageryType
()
=
Imagery
::
OFFLINE_SATELLITE
;
break
;
}
globalViewParams
->
imageryPath
()
=
dialog
.
mPathLineEdit
->
text
();
imageryOffset
.
setX
(
dialog
.
mXOffsetSpinBox
->
value
());
imageryOffset
.
setY
(
dialog
.
mYOffsetSpinBox
->
value
());
imageryOffset
.
setZ
(
dialog
.
mZOffsetSpinBox
->
value
());
globalViewParams
->
signalImageryParamsChanged
();
}
}
void
ImageryParamDialog
::
selectPath
(
void
)
{
QString
filename
=
QFileDialog
::
getExistingDirectory
(
this
,
"Imagery path"
,
QDesktopServices
::
storageLocation
(
QDesktopServices
::
DesktopLocation
));
if
(
filename
.
isNull
())
{
return
;
}
else
{
mPathLineEdit
->
setText
(
filename
);
}
}
void
ImageryParamDialog
::
closeWithSaving
(
void
)
{
done
(
QDialog
::
Accepted
);
}
void
ImageryParamDialog
::
closeWithoutSaving
(
void
)
{
done
(
QDialog
::
Rejected
);
}
void
ImageryParamDialog
::
buildLayout
(
QVBoxLayout
*
layout
)
{
QFormLayout
*
formLayout
=
new
QFormLayout
;
mImageryTypeComboBox
=
new
QComboBox
(
this
);
mImageryTypeComboBox
->
addItem
(
"None"
);
mImageryTypeComboBox
->
addItem
(
"Map (Google)"
);
mImageryTypeComboBox
->
addItem
(
"Satellite (Google)"
);
mImageryTypeComboBox
->
addItem
(
"Satellite (Offline)"
);
mPathLineEdit
=
new
QLineEdit
(
this
);
mPathLineEdit
->
setReadOnly
(
true
);
QPushButton
*
pathButton
=
new
QPushButton
(
this
);
pathButton
->
setText
(
tr
(
".."
));
QHBoxLayout
*
pathLayout
=
new
QHBoxLayout
;
pathLayout
->
addWidget
(
mPathLineEdit
);
pathLayout
->
addWidget
(
pathButton
);
formLayout
->
addRow
(
tr
(
"Imagery Type"
),
mImageryTypeComboBox
);
formLayout
->
addRow
(
tr
(
"Path"
),
pathLayout
);
layout
->
addLayout
(
formLayout
);
QGroupBox
*
offsetGroupBox
=
new
QGroupBox
(
tr
(
"Offset"
),
this
);
mXOffsetSpinBox
=
new
QDoubleSpinBox
(
this
);
mXOffsetSpinBox
->
setDecimals
(
1
);
mXOffsetSpinBox
->
setRange
(
-
1000.0
,
1000.0
);
mXOffsetSpinBox
->
setValue
(
0.0
);
mYOffsetSpinBox
=
new
QDoubleSpinBox
(
this
);
mYOffsetSpinBox
->
setDecimals
(
1
);
mYOffsetSpinBox
->
setRange
(
-
1000.0
,
1000.0
);
mYOffsetSpinBox
->
setValue
(
0.0
);
mZOffsetSpinBox
=
new
QDoubleSpinBox
(
this
);
mZOffsetSpinBox
->
setDecimals
(
1
);
mZOffsetSpinBox
->
setRange
(
-
1000.0
,
1000.0
);
mZOffsetSpinBox
->
setValue
(
0.0
);
formLayout
=
new
QFormLayout
;
formLayout
->
addRow
(
tr
(
"x (m)"
),
mXOffsetSpinBox
);
formLayout
->
addRow
(
tr
(
"y (m)"
),
mYOffsetSpinBox
);
formLayout
->
addRow
(
tr
(
"z (m)"
),
mZOffsetSpinBox
);
offsetGroupBox
->
setLayout
(
formLayout
);
layout
->
addWidget
(
offsetGroupBox
);
layout
->
addItem
(
new
QSpacerItem
(
10
,
0
,
QSizePolicy
::
Expanding
,
QSizePolicy
::
Expanding
));
QPushButton
*
cancelButton
=
new
QPushButton
(
this
);
cancelButton
->
setText
(
"Cancel"
);
QPushButton
*
saveButton
=
new
QPushButton
(
this
);
saveButton
->
setText
(
"Save"
);
QHBoxLayout
*
buttonLayout
=
new
QHBoxLayout
;
buttonLayout
->
addWidget
(
cancelButton
);
buttonLayout
->
addItem
(
new
QSpacerItem
(
10
,
0
,
QSizePolicy
::
Expanding
,
QSizePolicy
::
Expanding
));
buttonLayout
->
addWidget
(
saveButton
);
layout
->
addLayout
(
buttonLayout
);
connect
(
pathButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
selectPath
()));
connect
(
cancelButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
closeWithoutSaving
()));
connect
(
saveButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
closeWithSaving
()));
}
src/ui/map3D/ImageryParamDialog.h
0 → 100644
View file @
db075953
#ifndef IMAGERYPARAMDIALOG_H
#define IMAGERYPARAMDIALOG_H
#include <QComboBox>
#include <QDoubleSpinBox>
#include <QDialog>
#include <QLineEdit>
#include <QVBoxLayout>
#include "GlobalViewParams.h"
class
ImageryParamDialog
:
public
QDialog
{
Q_OBJECT
public:
ImageryParamDialog
(
QWidget
*
parent
=
0
);
static
void
getImageryParams
(
GlobalViewParamsPtr
&
globalViewParams
);
private
slots
:
void
selectPath
(
void
);
void
closeWithSaving
(
void
);
void
closeWithoutSaving
(
void
);
private:
void
buildLayout
(
QVBoxLayout
*
layout
);
QComboBox
*
mImageryTypeComboBox
;
QLineEdit
*
mPathLineEdit
;
QDoubleSpinBox
*
mXOffsetSpinBox
;
QDoubleSpinBox
*
mYOffsetSpinBox
;
QDoubleSpinBox
*
mZOffsetSpinBox
;
};
#endif // IMAGERYPARAMDIALOG_H
src/ui/map3D/Pixhawk3DWidget.cc
View file @
db075953
...
@@ -91,6 +91,8 @@ Pixhawk3DWidget::Pixhawk3DWidget(QWidget* parent)
...
@@ -91,6 +91,8 @@ Pixhawk3DWidget::Pixhawk3DWidget(QWidget* parent)
this
,
SLOT
(
systemCreated
(
UASInterface
*
)));
this
,
SLOT
(
systemCreated
(
UASInterface
*
)));
connect
(
mGlobalViewParams
.
data
(),
SIGNAL
(
followCameraChanged
(
int
)),
connect
(
mGlobalViewParams
.
data
(),
SIGNAL
(
followCameraChanged
(
int
)),
this
,
SLOT
(
followCameraChanged
(
int
)));
this
,
SLOT
(
followCameraChanged
(
int
)));
connect
(
mGlobalViewParams
.
data
(),
SIGNAL
(
imageryParamsChanged
(
void
)),
this
,
SLOT
(
imageryParamsChanged
(
void
)));
MainWindow
*
parentWindow
=
qobject_cast
<
MainWindow
*>
(
parent
);
MainWindow
*
parentWindow
=
qobject_cast
<
MainWindow
*>
(
parent
);
parentWindow
->
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
mViewParamWidget
);
parentWindow
->
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
mViewParamWidget
);
...
@@ -139,11 +141,14 @@ Pixhawk3DWidget::systemCreated(UASInterface *uas)
...
@@ -139,11 +141,14 @@ Pixhawk3DWidget::systemCreated(UASInterface *uas)
this
,
SLOT
(
attitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
this
,
SLOT
(
attitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
userPositionSetPointsChanged
(
int
,
float
,
float
,
float
,
float
)),
connect
(
uas
,
SIGNAL
(
userPositionSetPointsChanged
(
int
,
float
,
float
,
float
,
float
)),
this
,
SLOT
(
setpointChanged
(
int
,
float
,
float
,
float
,
float
)));
this
,
SLOT
(
setpointChanged
(
int
,
float
,
float
,
float
,
float
)));
connect
(
uas
,
SIGNAL
(
homePositionChanged
(
int
,
double
,
double
,
double
)),
this
,
SLOT
(
homePositionChanged
(
int
,
double
,
double
,
double
)));
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
connect
(
uas
,
SIGNAL
(
overlayChanged
(
UASInterface
*
)),
connect
(
uas
,
SIGNAL
(
overlayChanged
(
UASInterface
*
)),
this
,
SLOT
(
addOverlay
(
UASInterface
*
)));
this
,
SLOT
(
addOverlay
(
UASInterface
*
)));
#endif
#endif
// mSystemContainerMap[systemId].gpsLocalOrigin() = QVector3D(47.419182, 8.566980, 428);
initializeSystem
(
systemId
,
uas
->
getColor
());
initializeSystem
(
systemId
,
uas
->
getColor
());
emit
systemCreatedSignal
(
uas
);
emit
systemCreatedSignal
(
uas
);
...
@@ -341,6 +346,20 @@ Pixhawk3DWidget::attitudeChanged(UASInterface* uas,
...
@@ -341,6 +346,20 @@ Pixhawk3DWidget::attitudeChanged(UASInterface* uas,
m3DWidget
->
systemGroup
(
systemId
)
->
attitude
()
->
setAttitude
(
q
);
m3DWidget
->
systemGroup
(
systemId
)
->
attitude
()
->
setAttitude
(
q
);
}
}
void
Pixhawk3DWidget
::
homePositionChanged
(
int
uasId
,
double
lat
,
double
lon
,
double
alt
)
{
if
(
!
mSystemContainerMap
.
contains
(
uasId
))
{
return
;
}
SystemContainer
&
systemData
=
mSystemContainerMap
[
uasId
];
systemData
.
gpsLocalOrigin
()
=
QVector3D
(
lat
,
lon
,
alt
);
}
void
void
Pixhawk3DWidget
::
setpointChanged
(
int
uasId
,
float
x
,
float
y
,
float
z
,
Pixhawk3DWidget
::
setpointChanged
(
int
uasId
,
float
x
,
float
y
,
float
z
,
float
yaw
)
float
yaw
)
...
@@ -424,12 +443,13 @@ Pixhawk3DWidget::showTerrainParamWindow(void)
...
@@ -424,12 +443,13 @@ Pixhawk3DWidget::showTerrainParamWindow(void)
{
{
TerrainParamDialog
::
getTerrainParams
(
mGlobalViewParams
);
TerrainParamDialog
::
getTerrainParams
(
mGlobalViewParams
);
const
QVector4D
&
terrainOffset
=
mGlobalViewParams
->
terrainOffset
();
const
QVector3D
&
positionOffset
=
mGlobalViewParams
->
terrainPositionOffset
();
const
QVector3D
&
attitudeOffset
=
mGlobalViewParams
->
terrainAttitudeOffset
();
mTerrainPAT
->
setPosition
(
osg
::
Vec3d
(
terrainOffset
.
y
(),
terrainOffset
.
x
(),
-
terrai
nOffset
.
z
()));
mTerrainPAT
->
setPosition
(
osg
::
Vec3d
(
positionOffset
.
y
(),
positionOffset
.
x
(),
-
positio
nOffset
.
z
()));
mTerrainPAT
->
setAttitude
(
osg
::
Quat
(
M_PI_2
-
terrainOffset
.
w
(),
osg
::
Vec3d
(
0.0
f
,
0.0
f
,
1.0
f
),
mTerrainPAT
->
setAttitude
(
osg
::
Quat
(
M_PI_2
-
attitudeOffset
.
z
(),
osg
::
Vec3d
(
0.0
f
,
0.0
f
,
1.0
f
),
0.0
,
osg
::
Vec3d
(
1.0
f
,
0.0
f
,
0.0
f
),
attitudeOffset
.
y
()
,
osg
::
Vec3d
(
1.0
f
,
0.0
f
,
0.0
f
),
0.0
,
osg
::
Vec3d
(
0.0
f
,
1.0
f
,
0.0
f
)));
attitudeOffset
.
x
()
,
osg
::
Vec3d
(
0.0
f
,
1.0
f
,
0.0
f
)));
}
}
void
void
...
@@ -472,6 +492,16 @@ Pixhawk3DWidget::followCameraChanged(int systemId)
...
@@ -472,6 +492,16 @@ Pixhawk3DWidget::followCameraChanged(int systemId)
}
}
}
}
void
Pixhawk3DWidget
::
imageryParamsChanged
(
void
)
{
mImageryNode
->
setImageryType
(
mGlobalViewParams
->
imageryType
());
mImageryNode
->
setPath
(
mGlobalViewParams
->
imageryPath
());
const
QVector3D
&
offset
=
mGlobalViewParams
->
imageryOffset
();
mImageryNode
->
setOffset
(
offset
.
x
(),
offset
.
y
(),
offset
.
z
());
}
void
void
Pixhawk3DWidget
::
recenterActiveCamera
(
void
)
Pixhawk3DWidget
::
recenterActiveCamera
(
void
)
{
{
...
@@ -542,7 +572,8 @@ Pixhawk3DWidget::loadTerrainModel(void)
...
@@ -542,7 +572,8 @@ Pixhawk3DWidget::loadTerrainModel(void)
mTerrainNode
->
setName
(
"terrain"
);
mTerrainNode
->
setName
(
"terrain"
);
mTerrainPAT
->
addChild
(
mTerrainNode
);
mTerrainPAT
->
addChild
(
mTerrainNode
);
mGlobalViewParams
->
terrainOffset
()
=
QVector4D
();
mGlobalViewParams
->
terrainPositionOffset
()
=
QVector3D
();
mGlobalViewParams
->
terrainAttitudeOffset
()
=
QVector3D
();
mTerrainPAT
->
setPosition
(
osg
::
Vec3d
(
0.0
,
0.0
,
0.0
));
mTerrainPAT
->
setPosition
(
osg
::
Vec3d
(
0.0
,
0.0
,
0.0
));
mTerrainPAT
->
setAttitude
(
osg
::
Quat
(
M_PI_2
,
osg
::
Vec3d
(
0.0
f
,
0.0
f
,
1.0
f
),
mTerrainPAT
->
setAttitude
(
osg
::
Quat
(
M_PI_2
,
osg
::
Vec3d
(
0.0
f
,
0.0
f
,
1.0
f
),
...
@@ -987,8 +1018,6 @@ Pixhawk3DWidget::update(void)
...
@@ -987,8 +1018,6 @@ Pixhawk3DWidget::update(void)
#endif
#endif
}
}
mImageryNode
->
setImageryType
(
mGlobalViewParams
->
imageryType
());
if
(
mFollowCameraId
!=
-
1
)
if
(
mFollowCameraId
!=
-
1
)
{
{
UASInterface
*
uas
=
UASManager
::
instance
()
->
getUASForId
(
mFollowCameraId
);
UASInterface
*
uas
=
UASManager
::
instance
()
->
getUASForId
(
mFollowCameraId
);
...
@@ -1097,13 +1126,27 @@ Pixhawk3DWidget::update(void)
...
@@ -1097,13 +1126,27 @@ Pixhawk3DWidget::update(void)
updateRGBD
(
uas
,
frame
,
systemData
.
rgbImageNode
(),
updateRGBD
(
uas
,
frame
,
systemData
.
rgbImageNode
(),
systemData
.
depthImageNode
());
systemData
.
depthImageNode
());
}
}
if
(
frame
==
MAV_FRAME_LOCAL_NED
&&
mGlobalViewParams
->
imageryType
()
!=
Imagery
::
BLANK_MAP
&&
!
systemData
.
gpsLocalOrigin
().
isNull
()
&&
mActiveUAS
->
getUASID
()
==
systemId
)
{
const
QVector3D
&
gpsLocalOrigin
=
systemData
.
gpsLocalOrigin
();
double
utmX
,
utmY
;
QString
utmZone
;
Imagery
::
LLtoUTM
(
gpsLocalOrigin
.
x
(),
gpsLocalOrigin
.
y
(),
utmX
,
utmY
,
utmZone
);
updateImagery
(
utmX
,
utmY
,
utmZone
,
frame
);
}
#endif
#endif
}
}
if
(
frame
==
MAV_FRAME_GLOBAL
&&
if
(
frame
==
MAV_FRAME_GLOBAL
&&
mGlobalViewParams
->
imageryType
()
!=
Imagery
::
BLANK_MAP
)
mGlobalViewParams
->
imageryType
()
!=
Imagery
::
BLANK_MAP
)
{
{
// updateImagery(
robotX, robotY, robotZ
, utmZone);
// updateImagery(
x, y, z
, utmZone);
}
}
if
(
mActiveUAS
)
if
(
mActiveUAS
)
...
@@ -2009,8 +2052,8 @@ Pixhawk3DWidget::updateTrails(double robotX, double robotY, double robotZ,
...
@@ -2009,8 +2052,8 @@ Pixhawk3DWidget::updateTrails(double robotX, double robotY, double robotZ,
}
}
void
void
Pixhawk3DWidget
::
updateImagery
(
double
originX
,
double
originY
,
double
originZ
,
Pixhawk3DWidget
::
updateImagery
(
double
originX
,
double
originY
,
const
QString
&
zone
)
const
QString
&
zone
,
MAV_FRAME
frame
)
{
{
if
(
mImageryNode
->
getImageryType
()
==
Imagery
::
BLANK_MAP
)
if
(
mImageryNode
->
getImageryType
()
==
Imagery
::
BLANK_MAP
)
{
{
...
@@ -2018,9 +2061,9 @@ Pixhawk3DWidget::updateImagery(double originX, double originY, double originZ,
...
@@ -2018,9 +2061,9 @@ Pixhawk3DWidget::updateImagery(double originX, double originY, double originZ,
}
}
double
viewingRadius
=
m3DWidget
->
cameraManipulator
()
->
getDistance
()
*
10.0
;
double
viewingRadius
=
m3DWidget
->
cameraManipulator
()
->
getDistance
()
*
10.0
;
if
(
viewingRadius
<
1
00.0
)
if
(
viewingRadius
<
2
00.0
)
{
{
viewingRadius
=
1
00.0
;
viewingRadius
=
2
00.0
;
}
}
double
minResolution
=
0.25
;
double
minResolution
=
0.25
;
...
@@ -2036,7 +2079,7 @@ Pixhawk3DWidget::updateImagery(double originX, double originY, double originZ,
...
@@ -2036,7 +2079,7 @@ Pixhawk3DWidget::updateImagery(double originX, double originY, double originZ,
case
Imagery
:
:
GOOGLE_SATELLITE
:
case
Imagery
:
:
GOOGLE_SATELLITE
:
minResolution
=
0.5
;
minResolution
=
0.5
;
break
;
break
;
case
Imagery
:
:
SWISSTOPO
_SATELLITE
:
case
Imagery
:
:
OFFLINE
_SATELLITE
:
minResolution
=
0.25
;
minResolution
=
0.25
;
maxResolution
=
0.25
;
maxResolution
=
0.25
;
break
;
break
;
...
@@ -2055,13 +2098,24 @@ Pixhawk3DWidget::updateImagery(double originX, double originY, double originZ,
...
@@ -2055,13 +2098,24 @@ Pixhawk3DWidget::updateImagery(double originX, double originY, double originZ,
resolution
=
maxResolution
;
resolution
=
maxResolution
;
}
}
double
x
=
m3DWidget
->
cameraManipulator
()
->
getCenter
().
y
();
double
y
=
m3DWidget
->
cameraManipulator
()
->
getCenter
().
x
();
double
xOffset
=
0.0
;
double
yOffset
=
0.0
;
if
(
frame
==
MAV_FRAME_LOCAL_NED
)
{
xOffset
=
originX
;
yOffset
=
originY
;
}
mImageryNode
->
draw3D
(
viewingRadius
,
mImageryNode
->
draw3D
(
viewingRadius
,
resolution
,
resolution
,
m3DWidget
->
cameraManipulator
()
->
getCenter
().
y
(),
x
+
xOffset
,
m3DWidget
->
cameraManipulator
()
->
getCenter
().
x
(),
y
+
yOffset
,
originX
,
-
xOffset
,
originY
,
-
yOffset
,
originZ
,
zone
);
zone
);
// prefetch map tiles
// prefetch map tiles
...
@@ -2069,16 +2123,16 @@ Pixhawk3DWidget::updateImagery(double originX, double originY, double originZ,
...
@@ -2069,16 +2123,16 @@ Pixhawk3DWidget::updateImagery(double originX, double originY, double originZ,
{
{
mImageryNode
->
prefetch3D
(
viewingRadius
/
2.0
,
mImageryNode
->
prefetch3D
(
viewingRadius
/
2.0
,
resolution
/
2.0
,
resolution
/
2.0
,
m3DWidget
->
cameraManipulator
()
->
getCenter
().
y
()
,
x
+
xOffset
,
m3DWidget
->
cameraManipulator
()
->
getCenter
().
x
()
,
y
+
yOffset
,
zone
);
zone
);
}
}
if
(
resolution
*
2.0
<=
maxResolution
)
if
(
resolution
*
2.0
<=
maxResolution
)
{
{
mImageryNode
->
prefetch3D
(
viewingRadius
*
2.0
,
mImageryNode
->
prefetch3D
(
viewingRadius
*
2.0
,
resolution
*
2.0
,
resolution
*
2.0
,
m3DWidget
->
cameraManipulator
()
->
getCenter
().
y
()
,
x
+
xOffset
,
m3DWidget
->
cameraManipulator
()
->
getCenter
().
x
()
,
y
+
yOffset
,
zone
);
zone
);
}
}
...
...
src/ui/map3D/Pixhawk3DWidget.h
View file @
db075953
...
@@ -60,6 +60,7 @@ public slots:
...
@@ -60,6 +60,7 @@ public slots:
void
localPositionChanged
(
UASInterface
*
uas
,
double
x
,
double
y
,
double
z
,
quint64
time
);
void
localPositionChanged
(
UASInterface
*
uas
,
double
x
,
double
y
,
double
z
,
quint64
time
);
void
attitudeChanged
(
UASInterface
*
uas
,
int
component
,
double
roll
,
double
pitch
,
double
yaw
,
quint64
time
);
void
attitudeChanged
(
UASInterface
*
uas
,
int
component
,
double
roll
,
double
pitch
,
double
yaw
,
quint64
time
);
void
attitudeChanged
(
UASInterface
*
uas
,
double
roll
,
double
pitch
,
double
yaw
,
quint64
time
);
void
attitudeChanged
(
UASInterface
*
uas
,
double
roll
,
double
pitch
,
double
yaw
,
quint64
time
);
void
homePositionChanged
(
int
uasId
,
double
lat
,
double
lon
,
double
alt
);
void
setpointChanged
(
int
uasId
,
float
x
,
float
y
,
float
z
,
float
yaw
);
void
setpointChanged
(
int
uasId
,
float
x
,
float
y
,
float
z
,
float
yaw
);
signals:
signals:
...
@@ -71,6 +72,7 @@ private slots:
...
@@ -71,6 +72,7 @@ private slots:
void
showTerrainParamWindow
(
void
);
void
showTerrainParamWindow
(
void
);
void
showViewParamWindow
(
void
);
void
showViewParamWindow
(
void
);
void
followCameraChanged
(
int
systemId
);
void
followCameraChanged
(
int
systemId
);
void
imageryParamsChanged
(
void
);
void
recenterActiveCamera
(
void
);
void
recenterActiveCamera
(
void
);
void
modelChanged
(
int
systemId
,
int
index
);
void
modelChanged
(
int
systemId
,
int
index
);
void
setBirdEyeView
(
void
);
void
setBirdEyeView
(
void
);
...
@@ -143,8 +145,8 @@ private:
...
@@ -143,8 +145,8 @@ private:
void
resizeHUD
(
int
width
,
int
height
);
void
resizeHUD
(
int
width
,
int
height
);
void
updateHUD
(
UASInterface
*
uas
,
MAV_FRAME
frame
);
void
updateHUD
(
UASInterface
*
uas
,
MAV_FRAME
frame
);
void
updateImagery
(
double
originX
,
double
originY
,
double
originZ
,
void
updateImagery
(
double
originX
,
double
originY
,
const
QString
&
zone
);
const
QString
&
zone
,
MAV_FRAME
frame
);
void
updateTarget
(
UASInterface
*
uas
,
MAV_FRAME
frame
,
void
updateTarget
(
UASInterface
*
uas
,
MAV_FRAME
frame
,
double
robotX
,
double
robotY
,
double
robotZ
,
double
robotX
,
double
robotY
,
double
robotZ
,
QVector4D
&
target
,
QVector4D
&
target
,
...
...
src/ui/map3D/Q3DWidget.cc
View file @
db075953
...
@@ -61,7 +61,7 @@ Q3DWidget::Q3DWidget(QWidget* parent)
...
@@ -61,7 +61,7 @@ Q3DWidget::Q3DWidget(QWidget* parent)
mOsgGW
=
new
osgViewer
::
GraphicsWindowEmbedded
(
0
,
0
,
width
(),
height
());
mOsgGW
=
new
osgViewer
::
GraphicsWindowEmbedded
(
0
,
0
,
width
(),
height
());
setThreadingModel
(
osgViewer
::
Viewer
::
SingleThreaded
);
setThreadingModel
(
osgViewer
::
Viewer
::
CullDrawThreadPerContext
);
setMouseTracking
(
true
);
setMouseTracking
(
true
);
}
}
...
...
src/ui/map3D/SystemContainer.cc
View file @
db075953
...
@@ -7,6 +7,12 @@ SystemContainer::SystemContainer()
...
@@ -7,6 +7,12 @@ SystemContainer::SystemContainer()
}
}
QVector3D
&
SystemContainer
::
gpsLocalOrigin
(
void
)
{
return
mGPSLocalOrigin
;
}
QVector4D
&
QVector4D
&
SystemContainer
::
target
(
void
)
SystemContainer
::
target
(
void
)
{
{
...
...
src/ui/map3D/SystemContainer.h
View file @
db075953
...
@@ -4,6 +4,7 @@
...
@@ -4,6 +4,7 @@
#include <osg/Geode>
#include <osg/Geode>
#include <QMap>
#include <QMap>
#include <QVarLengthArray>
#include <QVarLengthArray>
#include <QVector3D>
#include <QVector4D>
#include <QVector4D>
#include "ImageWindowGeode.h"
#include "ImageWindowGeode.h"
...
@@ -19,6 +20,8 @@ class SystemContainer
...
@@ -19,6 +20,8 @@ class SystemContainer
public:
public:
SystemContainer
();
SystemContainer
();
QVector3D
&
gpsLocalOrigin
(
void
);
QVector4D
&
target
(
void
);
QVector4D
&
target
(
void
);
QVector
<
osg
::
ref_ptr
<
osg
::
Node
>
>&
models
(
void
);
QVector
<
osg
::
ref_ptr
<
osg
::
Node
>
>&
models
(
void
);
...
@@ -43,6 +46,7 @@ public:
...
@@ -43,6 +46,7 @@ public:
#endif
#endif
private:
private:
QVector3D
mGPSLocalOrigin
;
QVector4D
mTarget
;
QVector4D
mTarget
;
QVector
<
osg
::
ref_ptr
<
osg
::
Node
>
>
mModels
;
QVector
<
osg
::
ref_ptr
<
osg
::
Node
>
>
mModels
;
...
...
src/ui/map3D/TerrainParamDialog.cc
View file @
db075953
...
@@ -19,20 +19,25 @@ TerrainParamDialog::TerrainParamDialog(QWidget* parent)
...
@@ -19,20 +19,25 @@ TerrainParamDialog::TerrainParamDialog(QWidget* parent)
void
void
TerrainParamDialog
::
getTerrainParams
(
GlobalViewParamsPtr
&
globalViewParams
)
TerrainParamDialog
::
getTerrainParams
(
GlobalViewParamsPtr
&
globalViewParams
)
{
{
QVector4D
&
terrainOffset
=
globalViewParams
->
terrainOffset
();
QVector3D
&
positionOffset
=
globalViewParams
->
terrainPositionOffset
();
QVector3D
&
attitudeOffset
=
globalViewParams
->
terrainAttitudeOffset
();
TerrainParamDialog
dialog
;
TerrainParamDialog
dialog
;
dialog
.
mXOffsetSpinBox
->
setValue
(
terrainOffset
.
x
());
dialog
.
mXOffsetSpinBox
->
setValue
(
positionOffset
.
x
());
dialog
.
mYOffsetSpinBox
->
setValue
(
terrainOffset
.
y
());
dialog
.
mYOffsetSpinBox
->
setValue
(
positionOffset
.
y
());
dialog
.
mZOffsetSpinBox
->
setValue
(
terrainOffset
.
z
());
dialog
.
mZOffsetSpinBox
->
setValue
(
positionOffset
.
z
());
dialog
.
mYawOffsetSpinBox
->
setValue
(
osg
::
RadiansToDegrees
(
terrainOffset
.
w
()));
dialog
.
mRollOffsetSpinBox
->
setValue
(
osg
::
RadiansToDegrees
(
attitudeOffset
.
x
()));
dialog
.
mPitchOffsetSpinBox
->
setValue
(
osg
::
RadiansToDegrees
(
attitudeOffset
.
y
()));
dialog
.
mYawOffsetSpinBox
->
setValue
(
osg
::
RadiansToDegrees
(
attitudeOffset
.
z
()));
if
(
dialog
.
exec
()
==
QDialog
::
Accepted
)
if
(
dialog
.
exec
()
==
QDialog
::
Accepted
)
{
{
terrainOffset
.
setX
(
dialog
.
mXOffsetSpinBox
->
value
());
positionOffset
.
setX
(
dialog
.
mXOffsetSpinBox
->
value
());
terrainOffset
.
setY
(
dialog
.
mYOffsetSpinBox
->
value
());
positionOffset
.
setY
(
dialog
.
mYOffsetSpinBox
->
value
());
terrainOffset
.
setZ
(
dialog
.
mZOffsetSpinBox
->
value
());
positionOffset
.
setZ
(
dialog
.
mZOffsetSpinBox
->
value
());
terrainOffset
.
setW
(
osg
::
DegreesToRadians
(
dialog
.
mYawOffsetSpinBox
->
value
()));
attitudeOffset
.
setX
(
osg
::
DegreesToRadians
(
dialog
.
mRollOffsetSpinBox
->
value
()));
attitudeOffset
.
setY
(
osg
::
DegreesToRadians
(
dialog
.
mPitchOffsetSpinBox
->
value
()));
attitudeOffset
.
setZ
(
osg
::
DegreesToRadians
(
dialog
.
mYawOffsetSpinBox
->
value
()));
}
}
}
}
...
@@ -68,6 +73,16 @@ TerrainParamDialog::buildLayout(QVBoxLayout* layout)
...
@@ -68,6 +73,16 @@ TerrainParamDialog::buildLayout(QVBoxLayout* layout)
mZOffsetSpinBox
->
setRange
(
-
100.0
,
100.0
);
mZOffsetSpinBox
->
setRange
(
-
100.0
,
100.0
);
mZOffsetSpinBox
->
setValue
(
0.0
);
mZOffsetSpinBox
->
setValue
(
0.0
);
mRollOffsetSpinBox
=
new
QDoubleSpinBox
(
this
);
mRollOffsetSpinBox
->
setDecimals
(
0
);
mRollOffsetSpinBox
->
setRange
(
-
180.0
,
180.0
);
mRollOffsetSpinBox
->
setValue
(
0.0
);
mPitchOffsetSpinBox
=
new
QDoubleSpinBox
(
this
);
mPitchOffsetSpinBox
->
setDecimals
(
0
);
mPitchOffsetSpinBox
->
setRange
(
-
180.0
,
180.0
);
mPitchOffsetSpinBox
->
setValue
(
0.0
);
mYawOffsetSpinBox
=
new
QDoubleSpinBox
(
this
);
mYawOffsetSpinBox
=
new
QDoubleSpinBox
(
this
);
mYawOffsetSpinBox
->
setDecimals
(
0
);
mYawOffsetSpinBox
->
setDecimals
(
0
);
mYawOffsetSpinBox
->
setRange
(
-
180.0
,
180.0
);
mYawOffsetSpinBox
->
setRange
(
-
180.0
,
180.0
);
...
@@ -77,6 +92,8 @@ TerrainParamDialog::buildLayout(QVBoxLayout* layout)
...
@@ -77,6 +92,8 @@ TerrainParamDialog::buildLayout(QVBoxLayout* layout)
formLayout
->
addRow
(
tr
(
"x (m)"
),
mXOffsetSpinBox
);
formLayout
->
addRow
(
tr
(
"x (m)"
),
mXOffsetSpinBox
);
formLayout
->
addRow
(
tr
(
"y (m)"
),
mYOffsetSpinBox
);
formLayout
->
addRow
(
tr
(
"y (m)"
),
mYOffsetSpinBox
);
formLayout
->
addRow
(
tr
(
"z (m)"
),
mZOffsetSpinBox
);
formLayout
->
addRow
(
tr
(
"z (m)"
),
mZOffsetSpinBox
);
formLayout
->
addRow
(
tr
(
"Roll (deg)"
),
mRollOffsetSpinBox
);
formLayout
->
addRow
(
tr
(
"Pitch (deg)"
),
mPitchOffsetSpinBox
);
formLayout
->
addRow
(
tr
(
"Yaw (deg)"
),
mYawOffsetSpinBox
);
formLayout
->
addRow
(
tr
(
"Yaw (deg)"
),
mYawOffsetSpinBox
);
offsetGroupBox
->
setLayout
(
formLayout
);
offsetGroupBox
->
setLayout
(
formLayout
);
...
...
src/ui/map3D/TerrainParamDialog.h
View file @
db075953
...
@@ -26,6 +26,8 @@ private:
...
@@ -26,6 +26,8 @@ private:
QDoubleSpinBox
*
mXOffsetSpinBox
;
QDoubleSpinBox
*
mXOffsetSpinBox
;
QDoubleSpinBox
*
mYOffsetSpinBox
;
QDoubleSpinBox
*
mYOffsetSpinBox
;
QDoubleSpinBox
*
mZOffsetSpinBox
;
QDoubleSpinBox
*
mZOffsetSpinBox
;
QDoubleSpinBox
*
mRollOffsetSpinBox
;
QDoubleSpinBox
*
mPitchOffsetSpinBox
;
QDoubleSpinBox
*
mYawOffsetSpinBox
;
QDoubleSpinBox
*
mYawOffsetSpinBox
;
};
};
...
...
src/ui/map3D/Texture.cc
View file @
db075953
...
@@ -25,7 +25,7 @@ This file is part of the QGROUNDCONTROL project
...
@@ -25,7 +25,7 @@ This file is part of the QGROUNDCONTROL project
* @file
* @file
* @brief Definition of the class Texture.
* @brief Definition of the class Texture.
*
*
* @author Lionel Heng <hengli@
student
.ethz.ch>
* @author Lionel Heng <hengli@
inf
.ethz.ch>
*
*
*/
*/
...
@@ -33,77 +33,86 @@ This file is part of the QGROUNDCONTROL project
...
@@ -33,77 +33,86 @@ This file is part of the QGROUNDCONTROL project
#include "Texture.h"
#include "Texture.h"
Texture
::
Texture
(
unsigned
int
_
id
)
Texture
::
Texture
(
quint64
id
)
:
id
(
_
id
)
:
mId
(
id
)
,
t
exture2D
(
new
osg
::
Texture2D
)
,
mT
exture2D
(
new
osg
::
Texture2D
)
,
g
eometry
(
new
osg
::
Geometry
)
,
mG
eometry
(
new
osg
::
Geometry
)
{
{
t
exture2D
->
setFilter
(
osg
::
Texture
::
MIN_FILTER
,
osg
::
Texture
::
NEAREST
);
mT
exture2D
->
setFilter
(
osg
::
Texture
::
MIN_FILTER
,
osg
::
Texture
::
NEAREST
);
t
exture2D
->
setFilter
(
osg
::
Texture
::
MAG_FILTER
,
osg
::
Texture
::
NEAREST
);
mT
exture2D
->
setFilter
(
osg
::
Texture
::
MAG_FILTER
,
osg
::
Texture
::
NEAREST
);
t
exture2D
->
setDataVariance
(
osg
::
Object
::
DYNAMIC
);
mT
exture2D
->
setDataVariance
(
osg
::
Object
::
DYNAMIC
);
t
exture2D
->
setResizeNonPowerOfTwoHint
(
false
);
mT
exture2D
->
setResizeNonPowerOfTwoHint
(
false
);
osg
::
ref_ptr
<
osg
::
Image
>
image
=
new
osg
::
Image
;
osg
::
ref_ptr
<
osg
::
Image
>
image
=
new
osg
::
Image
;
t
exture2D
->
setImage
(
image
);
mT
exture2D
->
setImage
(
image
);
osg
::
ref_ptr
<
osg
::
Vec3dArray
>
vertices
(
new
osg
::
Vec3dArray
(
4
));
osg
::
ref_ptr
<
osg
::
Vec3dArray
>
vertices
(
new
osg
::
Vec3dArray
(
4
));
g
eometry
->
setVertexArray
(
vertices
);
mG
eometry
->
setVertexArray
(
vertices
);
osg
::
ref_ptr
<
osg
::
Vec2Array
>
textureCoords
=
new
osg
::
Vec2Array
;
osg
::
ref_ptr
<
osg
::
Vec2Array
>
textureCoords
=
new
osg
::
Vec2Array
;
textureCoords
->
push_back
(
osg
::
Vec2
(
0.0
f
,
1.0
f
));
textureCoords
->
push_back
(
osg
::
Vec2
(
0.0
f
,
1.0
f
));
textureCoords
->
push_back
(
osg
::
Vec2
(
1.0
f
,
1.0
f
));
textureCoords
->
push_back
(
osg
::
Vec2
(
1.0
f
,
1.0
f
));
textureCoords
->
push_back
(
osg
::
Vec2
(
1.0
f
,
0.0
f
));
textureCoords
->
push_back
(
osg
::
Vec2
(
1.0
f
,
0.0
f
));
textureCoords
->
push_back
(
osg
::
Vec2
(
0.0
f
,
0.0
f
));
textureCoords
->
push_back
(
osg
::
Vec2
(
0.0
f
,
0.0
f
));
g
eometry
->
setTexCoordArray
(
0
,
textureCoords
);
mG
eometry
->
setTexCoordArray
(
0
,
textureCoords
);
g
eometry
->
addPrimitiveSet
(
new
osg
::
DrawArrays
(
osg
::
PrimitiveSet
::
LINES
,
mG
eometry
->
addPrimitiveSet
(
new
osg
::
DrawArrays
(
osg
::
PrimitiveSet
::
LINES
,
0
,
4
));
0
,
4
));
osg
::
ref_ptr
<
osg
::
Vec4Array
>
colors
(
new
osg
::
Vec4Array
);
osg
::
ref_ptr
<
osg
::
Vec4Array
>
colors
(
new
osg
::
Vec4Array
);
colors
->
push_back
(
osg
::
Vec4
(
0.0
f
,
0.0
f
,
1.0
f
,
1.0
f
));
colors
->
push_back
(
osg
::
Vec4
(
0.0
f
,
0.0
f
,
1.0
f
,
1.0
f
));
g
eometry
->
setColorArray
(
colors
);
mG
eometry
->
setColorArray
(
colors
);
g
eometry
->
setColorBinding
(
osg
::
Geometry
::
BIND_OVERALL
);
mG
eometry
->
setColorBinding
(
osg
::
Geometry
::
BIND_OVERALL
);
g
eometry
->
setUseDisplayList
(
false
);
mG
eometry
->
setUseDisplayList
(
false
);
osg
::
ref_ptr
<
osg
::
LineWidth
>
linewidth
(
new
osg
::
LineWidth
);
osg
::
ref_ptr
<
osg
::
LineWidth
>
linewidth
(
new
osg
::
LineWidth
);
linewidth
->
setWidth
(
2.0
f
);
linewidth
->
setWidth
(
2.0
f
);
g
eometry
->
getOrCreateStateSet
()
->
mG
eometry
->
getOrCreateStateSet
()
->
setAttributeAndModes
(
linewidth
,
osg
::
StateAttribute
::
ON
);
setAttributeAndModes
(
linewidth
,
osg
::
StateAttribute
::
ON
);
g
eometry
->
getOrCreateStateSet
()
->
mG
eometry
->
getOrCreateStateSet
()
->
setMode
(
GL_LIGHTING
,
osg
::
StateAttribute
::
OFF
);
setMode
(
GL_LIGHTING
,
osg
::
StateAttribute
::
OFF
);
}
}
const
QString
&
const
QString
&
Texture
::
getSourceURL
(
void
)
const
Texture
::
getSourceURL
(
void
)
const
{
{
return
sourceURL
;
return
mSourceURL
;
}
void
Texture
::
setId
(
quint64
id
)
{
mId
=
id
;
}
}
void
void
Texture
::
sync
(
const
WebImagePtr
&
image
)
Texture
::
sync
(
const
WebImagePtr
&
image
)
{
{
s
tate
=
static_cast
<
State
>
(
image
->
getState
());
mS
tate
=
static_cast
<
State
>
(
image
->
getState
());
if
(
image
->
getState
()
!=
WebImage
::
UNINITIALIZED
&&
if
(
image
->
getState
()
!=
WebImage
::
UNINITIALIZED
&&
sourceURL
!=
image
->
getSourceURL
())
{
mSourceURL
!=
image
->
getSourceURL
())
sourceURL
=
image
->
getSourceURL
();
{
mSourceURL
=
image
->
getSourceURL
();
}
}
if
(
image
->
getState
()
==
WebImage
::
READY
&&
image
->
getSyncFlag
())
{
if
(
image
->
getState
()
==
WebImage
::
READY
&&
image
->
getSyncFlag
())
{
image
->
setSyncFlag
(
false
);
image
->
setSyncFlag
(
false
);
if
(
texture2D
->
getImage
()
!=
NULL
)
{
if
(
mTexture2D
->
getImage
()
!=
NULL
)
texture2D
->
getImage
()
->
setImage
(
image
->
getWidth
(),
{
image
->
getHeight
(),
mTexture2D
->
getImage
()
->
setImage
(
image
->
getWidth
(),
1
,
image
->
getHeight
(),
GL_RGBA
,
1
,
GL_RGBA
,
GL_RGBA
,
GL_UNSIGNED_BYTE
,
GL_RGBA
,
image
->
getImageData
(),
GL_UNSIGNED_BYTE
,
osg
::
Image
::
NO_DELETE
);
image
->
getImageData
(),
texture2D
->
getImage
()
->
dirty
();
osg
::
Image
::
NO_DELETE
);
mTexture2D
->
getImage
()
->
dirty
();
}
}
}
}
}
}
...
@@ -123,40 +132,44 @@ Texture::draw(double x1, double y1, double x2, double y2,
...
@@ -123,40 +132,44 @@ Texture::draw(double x1, double y1, double x2, double y2,
bool
smoothInterpolation
)
const
bool
smoothInterpolation
)
const
{
{
osg
::
Vec3dArray
*
vertices
=
osg
::
Vec3dArray
*
vertices
=
static_cast
<
osg
::
Vec3dArray
*>
(
g
eometry
->
getVertexArray
());
static_cast
<
osg
::
Vec3dArray
*>
(
mG
eometry
->
getVertexArray
());
(
*
vertices
)[
0
].
set
(
x1
,
y1
,
z
);
(
*
vertices
)[
0
].
set
(
x1
,
y1
,
z
);
(
*
vertices
)[
1
].
set
(
x2
,
y2
,
z
);
(
*
vertices
)[
1
].
set
(
x2
,
y2
,
z
);
(
*
vertices
)[
2
].
set
(
x3
,
y3
,
z
);
(
*
vertices
)[
2
].
set
(
x3
,
y3
,
z
);
(
*
vertices
)[
3
].
set
(
x4
,
y4
,
z
);
(
*
vertices
)[
3
].
set
(
x4
,
y4
,
z
);
osg
::
DrawArrays
*
drawarrays
=
osg
::
DrawArrays
*
drawarrays
=
static_cast
<
osg
::
DrawArrays
*>
(
g
eometry
->
getPrimitiveSet
(
0
));
static_cast
<
osg
::
DrawArrays
*>
(
mG
eometry
->
getPrimitiveSet
(
0
));
osg
::
Vec4Array
*
colors
=
osg
::
Vec4Array
*
colors
=
static_cast
<
osg
::
Vec4Array
*>
(
g
eometry
->
getColorArray
());
static_cast
<
osg
::
Vec4Array
*>
(
mG
eometry
->
getColorArray
());
if
(
state
==
REQUESTED
)
{
if
(
mState
==
REQUESTED
)
{
drawarrays
->
set
(
osg
::
PrimitiveSet
::
LINE_LOOP
,
0
,
4
);
drawarrays
->
set
(
osg
::
PrimitiveSet
::
LINE_LOOP
,
0
,
4
);
(
*
colors
)[
0
].
set
(
0.0
f
,
0.0
f
,
1.0
f
,
1.0
f
);
(
*
colors
)[
0
].
set
(
0.0
f
,
0.0
f
,
1.0
f
,
1.0
f
);
g
eometry
->
getOrCreateStateSet
()
->
mG
eometry
->
getOrCreateStateSet
()
->
setTextureAttributeAndModes
(
0
,
t
exture2D
,
osg
::
StateAttribute
::
OFF
);
setTextureAttributeAndModes
(
0
,
mT
exture2D
,
osg
::
StateAttribute
::
OFF
);
return
g
eometry
;
return
mG
eometry
;
}
}
if
(
smoothInterpolation
)
{
if
(
smoothInterpolation
)
texture2D
->
setFilter
(
osg
::
Texture
::
MIN_FILTER
,
osg
::
Texture
::
LINEAR
);
{
texture2D
->
setFilter
(
osg
::
Texture
::
MAG_FILTER
,
osg
::
Texture
::
LINEAR
);
mTexture2D
->
setFilter
(
osg
::
Texture
::
MIN_FILTER
,
osg
::
Texture
::
LINEAR
);
}
else
{
mTexture2D
->
setFilter
(
osg
::
Texture
::
MAG_FILTER
,
osg
::
Texture
::
LINEAR
);
texture2D
->
setFilter
(
osg
::
Texture
::
MIN_FILTER
,
osg
::
Texture
::
NEAREST
);
}
texture2D
->
setFilter
(
osg
::
Texture
::
MAG_FILTER
,
osg
::
Texture
::
NEAREST
);
else
{
mTexture2D
->
setFilter
(
osg
::
Texture
::
MIN_FILTER
,
osg
::
Texture
::
NEAREST
);
mTexture2D
->
setFilter
(
osg
::
Texture
::
MAG_FILTER
,
osg
::
Texture
::
NEAREST
);
}
}
drawarrays
->
set
(
osg
::
PrimitiveSet
::
POLYGON
,
0
,
4
);
drawarrays
->
set
(
osg
::
PrimitiveSet
::
POLYGON
,
0
,
4
);
(
*
colors
)[
0
].
set
(
1.0
f
,
1.0
f
,
1.0
f
,
1.0
f
);
(
*
colors
)[
0
].
set
(
1.0
f
,
1.0
f
,
1.0
f
,
1.0
f
);
g
eometry
->
getOrCreateStateSet
()
->
mG
eometry
->
getOrCreateStateSet
()
->
setTextureAttributeAndModes
(
0
,
t
exture2D
,
osg
::
StateAttribute
::
ON
);
setTextureAttributeAndModes
(
0
,
mT
exture2D
,
osg
::
StateAttribute
::
ON
);
return
g
eometry
;
return
mG
eometry
;
}
}
src/ui/map3D/Texture.h
View file @
db075953
...
@@ -25,7 +25,7 @@ This file is part of the QGROUNDCONTROL project
...
@@ -25,7 +25,7 @@ This file is part of the QGROUNDCONTROL project
* @file
* @file
* @brief Definition of the class Texture.
* @brief Definition of the class Texture.
*
*
* @author Lionel Heng <hengli@
student
.ethz.ch>
* @author Lionel Heng <hengli@
inf
.ethz.ch>
*
*
*/
*/
...
@@ -43,11 +43,11 @@ This file is part of the QGROUNDCONTROL project
...
@@ -43,11 +43,11 @@ This file is part of the QGROUNDCONTROL project
class
Texture
class
Texture
{
{
public:
public:
explicit
Texture
(
unsigned
int
_
id
);
explicit
Texture
(
quint64
id
);
const
QString
&
getSourceURL
(
void
)
const
;
const
QString
&
getSourceURL
(
void
)
const
;
void
setId
(
unsigned
int
_
id
);
void
setId
(
quint64
id
);
void
sync
(
const
WebImagePtr
&
image
);
void
sync
(
const
WebImagePtr
&
image
);
...
@@ -60,17 +60,18 @@ public:
...
@@ -60,17 +60,18 @@ public:
bool
smoothInterpolation
)
const
;
bool
smoothInterpolation
)
const
;
private:
private:
enum
State
{
enum
State
{
UNINITIALIZED
=
0
,
UNINITIALIZED
=
0
,
REQUESTED
=
1
,
REQUESTED
=
1
,
READY
=
2
READY
=
2
};
};
State
s
tate
;
State
mS
tate
;
QString
s
ourceURL
;
QString
mS
ourceURL
;
unsigned
int
i
d
;
quint64
mI
d
;
osg
::
ref_ptr
<
osg
::
Texture2D
>
t
exture2D
;
osg
::
ref_ptr
<
osg
::
Texture2D
>
mT
exture2D
;
osg
::
ref_ptr
<
osg
::
Geometry
>
g
eometry
;
osg
::
ref_ptr
<
osg
::
Geometry
>
mG
eometry
;
};
};
typedef
QSharedPointer
<
Texture
>
TexturePtr
;
typedef
QSharedPointer
<
Texture
>
TexturePtr
;
...
...
src/ui/map3D/TextureCache.cc
View file @
db075953
...
@@ -25,34 +25,37 @@ This file is part of the QGROUNDCONTROL project
...
@@ -25,34 +25,37 @@ This file is part of the QGROUNDCONTROL project
* @file
* @file
* @brief Definition of the class TextureCache.
* @brief Definition of the class TextureCache.
*
*
* @author Lionel Heng <hengli@
student
.ethz.ch>
* @author Lionel Heng <hengli@
inf
.ethz.ch>
*
*
*/
*/
#include "TextureCache.h"
#include "TextureCache.h"
TextureCache
::
TextureCache
(
uint32_t
_
cacheSize
)
TextureCache
::
TextureCache
(
int
cacheSize
)
:
cacheSize
(
_
cacheSize
)
:
mCacheSize
(
cacheSize
)
,
i
mageCache
(
new
WebImageCache
(
0
,
cacheSize
))
,
mI
mageCache
(
new
WebImageCache
(
0
,
cacheSize
))
{
{
for
(
uint32_t
i
=
0
;
i
<
cacheSize
;
++
i
)
{
for
(
int
i
=
0
;
i
<
mCacheSize
;
++
i
)
{
TexturePtr
t
(
new
Texture
(
i
));
TexturePtr
t
(
new
Texture
(
i
));
t
extures
.
push_back
(
t
);
mT
extures
.
push_back
(
t
);
}
}
}
}
TexturePtr
TexturePtr
TextureCache
::
get
(
const
QString
&
tileURL
)
TextureCache
::
get
(
const
QString
&
tileURL
)
{
{
QPair
<
TexturePtr
,
int32_t
>
p1
=
lookup
(
tileURL
);
QPair
<
TexturePtr
,
int
>
p1
=
lookup
(
tileURL
);
if
(
!
p1
.
first
.
isNull
())
{
if
(
!
p1
.
first
.
isNull
())
{
return
p1
.
first
;
return
p1
.
first
;
}
}
QPair
<
WebImagePtr
,
int32_t
>
p2
=
imageCache
->
lookup
(
tileURL
);
QPair
<
WebImagePtr
,
int
>
p2
=
mImageCache
->
lookup
(
tileURL
);
if
(
!
p2
.
first
.
isNull
())
{
if
(
!
p2
.
first
.
isNull
())
textures
[
p2
.
second
]
->
sync
(
p2
.
first
);
{
mTextures
[
p2
.
second
]
->
sync
(
p2
.
first
);
p1
=
lookup
(
tileURL
);
p1
=
lookup
(
tileURL
);
return
p1
.
first
;
return
p1
.
first
;
...
@@ -64,19 +67,23 @@ TextureCache::get(const QString& tileURL)
...
@@ -64,19 +67,23 @@ TextureCache::get(const QString& tileURL)
void
void
TextureCache
::
sync
(
void
)
TextureCache
::
sync
(
void
)
{
{
if
(
requireSync
())
{
if
(
requireSync
())
for
(
int32_t
i
=
0
;
i
<
textures
.
size
();
++
i
)
{
{
textures
[
i
]
->
sync
(
imageCache
->
at
(
i
));
for
(
int
i
=
0
;
i
<
mTextures
.
size
();
++
i
)
{
mTextures
[
i
]
->
sync
(
mImageCache
->
at
(
i
));
}
}
}
}
}
}
QPair
<
TexturePtr
,
int
32_t
>
QPair
<
TexturePtr
,
int
>
TextureCache
::
lookup
(
const
QString
&
tileURL
)
TextureCache
::
lookup
(
const
QString
&
tileURL
)
{
{
for
(
int32_t
i
=
0
;
i
<
textures
.
size
();
++
i
)
{
for
(
int
i
=
0
;
i
<
mTextures
.
size
();
++
i
)
if
(
textures
[
i
]
->
getSourceURL
()
==
tileURL
)
{
{
return
qMakePair
(
textures
[
i
],
i
);
if
(
mTextures
[
i
]
->
getSourceURL
()
==
tileURL
)
{
return
qMakePair
(
mTextures
[
i
],
i
);
}
}
}
}
...
@@ -86,8 +93,10 @@ TextureCache::lookup(const QString& tileURL)
...
@@ -86,8 +93,10 @@ TextureCache::lookup(const QString& tileURL)
bool
bool
TextureCache
::
requireSync
(
void
)
const
TextureCache
::
requireSync
(
void
)
const
{
{
for
(
uint32_t
i
=
0
;
i
<
cacheSize
;
++
i
)
{
for
(
int
i
=
0
;
i
<
mCacheSize
;
++
i
)
if
(
imageCache
->
at
(
i
)
->
getSyncFlag
())
{
{
if
(
mImageCache
->
at
(
i
)
->
getSyncFlag
())
{
return
true
;
return
true
;
}
}
}
}
...
...
src/ui/map3D/TextureCache.h
View file @
db075953
...
@@ -25,7 +25,7 @@ This file is part of the QGROUNDCONTROL project
...
@@ -25,7 +25,7 @@ This file is part of the QGROUNDCONTROL project
* @file
* @file
* @brief Definition of the class TextureCache.
* @brief Definition of the class TextureCache.
*
*
* @author Lionel Heng <hengli@
student
.ethz.ch>
* @author Lionel Heng <hengli@
inf
.ethz.ch>
*
*
*/
*/
...
@@ -40,7 +40,7 @@ This file is part of the QGROUNDCONTROL project
...
@@ -40,7 +40,7 @@ This file is part of the QGROUNDCONTROL project
class
TextureCache
class
TextureCache
{
{
public:
public:
explicit
TextureCache
(
uint32_
t
cacheSize
);
explicit
TextureCache
(
in
t
cacheSize
);
TexturePtr
get
(
const
QString
&
tileURL
);
TexturePtr
get
(
const
QString
&
tileURL
);
...
@@ -51,10 +51,10 @@ private:
...
@@ -51,10 +51,10 @@ private:
bool
requireSync
(
void
)
const
;
bool
requireSync
(
void
)
const
;
uint32_t
c
acheSize
;
int
mC
acheSize
;
QVector
<
TexturePtr
>
t
extures
;
QVector
<
TexturePtr
>
mT
extures
;
QScopedPointer
<
WebImageCache
>
i
mageCache
;
QScopedPointer
<
WebImageCache
>
mI
mageCache
;
};
};
#endif // TEXTURECACHE_H
#endif // TEXTURECACHE_H
src/ui/map3D/ViewParamWidget.cc
View file @
db075953
...
@@ -6,6 +6,7 @@
...
@@ -6,6 +6,7 @@
#include <QLabel>
#include <QLabel>
#include <QPushButton>
#include <QPushButton>
#include "ImageryParamDialog.h"
#include "UASInterface.h"
#include "UASInterface.h"
ViewParamWidget
::
ViewParamWidget
(
GlobalViewParamsPtr
&
globalViewParams
,
ViewParamWidget
::
ViewParamWidget
(
GlobalViewParamsPtr
&
globalViewParams
,
...
@@ -97,6 +98,12 @@ ViewParamWidget::setpointsCheckBoxToggled(int state)
...
@@ -97,6 +98,12 @@ ViewParamWidget::setpointsCheckBoxToggled(int state)
}
}
}
}
void
ViewParamWidget
::
showImageryParamDialog
(
void
)
{
ImageryParamDialog
::
getImageryParams
(
mGlobalViewParams
);
}
void
void
ViewParamWidget
::
buildLayout
(
QVBoxLayout
*
layout
)
ViewParamWidget
::
buildLayout
(
QVBoxLayout
*
layout
)
{
{
...
@@ -106,17 +113,15 @@ ViewParamWidget::buildLayout(QVBoxLayout* layout)
...
@@ -106,17 +113,15 @@ ViewParamWidget::buildLayout(QVBoxLayout* layout)
frameComboBox
->
addItem
(
"Local"
);
frameComboBox
->
addItem
(
"Local"
);
frameComboBox
->
addItem
(
"Global"
);
frameComboBox
->
addItem
(
"Global"
);
QComboBox
*
imageryComboBox
=
new
QComboBox
(
this
);
imageryComboBox
->
addItem
(
"None"
);
imageryComboBox
->
addItem
(
"Map (Google)"
);
imageryComboBox
->
addItem
(
"Satellite (Google)"
);
QCheckBox
*
terrainModelCheckBox
=
new
QCheckBox
(
this
);
QCheckBox
*
terrainModelCheckBox
=
new
QCheckBox
(
this
);
terrainModelCheckBox
->
setChecked
(
mGlobalViewParams
->
displayTerrain
());
terrainModelCheckBox
->
setChecked
(
mGlobalViewParams
->
displayTerrain
());
QCheckBox
*
worldGridCheckBox
=
new
QCheckBox
(
this
);
QCheckBox
*
worldGridCheckBox
=
new
QCheckBox
(
this
);
worldGridCheckBox
->
setChecked
(
mGlobalViewParams
->
displayWorldGrid
());
worldGridCheckBox
->
setChecked
(
mGlobalViewParams
->
displayWorldGrid
());
QPushButton
*
imageryButton
=
new
QPushButton
(
this
);
imageryButton
->
setText
(
"View"
);
QMapIterator
<
int
,
SystemViewParamsPtr
>
it
(
mSystemViewParamMap
);
QMapIterator
<
int
,
SystemViewParamsPtr
>
it
(
mSystemViewParamMap
);
while
(
it
.
hasNext
())
while
(
it
.
hasNext
())
{
{
...
@@ -130,9 +135,9 @@ ViewParamWidget::buildLayout(QVBoxLayout* layout)
...
@@ -130,9 +135,9 @@ ViewParamWidget::buildLayout(QVBoxLayout* layout)
QFormLayout
*
formLayout
=
new
QFormLayout
;
QFormLayout
*
formLayout
=
new
QFormLayout
;
formLayout
->
addRow
(
tr
(
"Follow Camera"
),
mFollowCameraComboBox
);
formLayout
->
addRow
(
tr
(
"Follow Camera"
),
mFollowCameraComboBox
);
formLayout
->
addRow
(
tr
(
"Frame"
),
frameComboBox
);
formLayout
->
addRow
(
tr
(
"Frame"
),
frameComboBox
);
formLayout
->
addRow
(
tr
(
"Imagery"
),
imageryComboBox
);
formLayout
->
addRow
(
tr
(
"Terrain"
),
terrainModelCheckBox
);
formLayout
->
addRow
(
tr
(
"Terrain"
),
terrainModelCheckBox
);
formLayout
->
addRow
(
tr
(
"World Grid"
),
worldGridCheckBox
);
formLayout
->
addRow
(
tr
(
"World Grid"
),
worldGridCheckBox
);
formLayout
->
addRow
(
tr
(
"Imagery Options"
),
imageryButton
);
layout
->
addLayout
(
formLayout
);
layout
->
addLayout
(
formLayout
);
layout
->
addWidget
(
mTabWidget
);
layout
->
addWidget
(
mTabWidget
);
...
@@ -142,12 +147,14 @@ ViewParamWidget::buildLayout(QVBoxLayout* layout)
...
@@ -142,12 +147,14 @@ ViewParamWidget::buildLayout(QVBoxLayout* layout)
mGlobalViewParams
.
data
(),
SLOT
(
followCameraChanged
(
const
QString
&
)));
mGlobalViewParams
.
data
(),
SLOT
(
followCameraChanged
(
const
QString
&
)));
connect
(
frameComboBox
,
SIGNAL
(
currentIndexChanged
(
const
QString
&
)),
connect
(
frameComboBox
,
SIGNAL
(
currentIndexChanged
(
const
QString
&
)),
mGlobalViewParams
.
data
(),
SLOT
(
frameChanged
(
const
QString
&
)));
mGlobalViewParams
.
data
(),
SLOT
(
frameChanged
(
const
QString
&
)));
connect
(
imageryComboBox
,
SIGNAL
(
currentIndexChanged
(
int
)),
mGlobalViewParams
.
data
(),
SLOT
(
imageryTypeChanged
(
int
)));
connect
(
terrainModelCheckBox
,
SIGNAL
(
stateChanged
(
int
)),
connect
(
terrainModelCheckBox
,
SIGNAL
(
stateChanged
(
int
)),
mGlobalViewParams
.
data
(),
SLOT
(
toggleTerrain
(
int
)));
mGlobalViewParams
.
data
(),
SLOT
(
toggleTerrain
(
int
)));
connect
(
worldGridCheckBox
,
SIGNAL
(
stateChanged
(
int
)),
connect
(
worldGridCheckBox
,
SIGNAL
(
stateChanged
(
int
)),
mGlobalViewParams
.
data
(),
SLOT
(
toggleWorldGrid
(
int
)));
mGlobalViewParams
.
data
(),
SLOT
(
toggleWorldGrid
(
int
)));
connect
(
imageryButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
showImageryParamDialog
()));
// connect(imageryComboBox, SIGNAL(currentIndexChanged(int)),
// mGlobalViewParams.data(), SLOT(imageryTypeChanged(int)));
}
}
void
void
...
...
src/ui/map3D/ViewParamWidget.h
View file @
db075953
...
@@ -31,6 +31,7 @@ private slots:
...
@@ -31,6 +31,7 @@ private slots:
void
overlayCreated
(
int
systemId
,
const
QString
&
name
);
void
overlayCreated
(
int
systemId
,
const
QString
&
name
);
void
systemCreated
(
UASInterface
*
uas
);
void
systemCreated
(
UASInterface
*
uas
);
void
setpointsCheckBoxToggled
(
int
state
);
void
setpointsCheckBoxToggled
(
int
state
);
void
showImageryParamDialog
(
void
);
private:
private:
void
buildLayout
(
QVBoxLayout
*
layout
);
void
buildLayout
(
QVBoxLayout
*
layout
);
...
...
src/ui/map3D/WebImage.cc
View file @
db075953
...
@@ -35,11 +35,11 @@ This file is part of the QGROUNDCONTROL project
...
@@ -35,11 +35,11 @@ This file is part of the QGROUNDCONTROL project
#include <QGLWidget>
#include <QGLWidget>
WebImage
::
WebImage
()
WebImage
::
WebImage
()
:
s
tate
(
WebImage
::
UNINITIALIZED
)
:
mS
tate
(
WebImage
::
UNINITIALIZED
)
,
s
ourceURL
(
""
)
,
mS
ourceURL
(
""
)
,
i
mage
(
0
)
,
mI
mage
(
0
)
,
l
astReference
(
0
)
,
mL
astReference
(
0
)
,
s
yncFlag
(
false
)
,
mS
yncFlag
(
false
)
{
{
}
}
...
@@ -47,54 +47,58 @@ WebImage::WebImage()
...
@@ -47,54 +47,58 @@ WebImage::WebImage()
void
void
WebImage
::
clear
(
void
)
WebImage
::
clear
(
void
)
{
{
i
mage
.
reset
();
mI
mage
.
reset
();
s
ourceURL
.
clear
();
mS
ourceURL
.
clear
();
s
tate
=
WebImage
::
UNINITIALIZED
;
mS
tate
=
WebImage
::
UNINITIALIZED
;
l
astReference
=
0
;
mL
astReference
=
0
;
}
}
WebImage
::
State
WebImage
::
State
WebImage
::
getState
(
void
)
const
WebImage
::
getState
(
void
)
const
{
{
return
s
tate
;
return
mS
tate
;
}
}
void
void
WebImage
::
setState
(
State
state
)
WebImage
::
setState
(
State
state
)
{
{
this
->
s
tate
=
state
;
mS
tate
=
state
;
}
}
const
QString
&
const
QString
&
WebImage
::
getSourceURL
(
void
)
const
WebImage
::
getSourceURL
(
void
)
const
{
{
return
s
ourceURL
;
return
mS
ourceURL
;
}
}
void
void
WebImage
::
setSourceURL
(
const
QString
&
url
)
WebImage
::
setSourceURL
(
const
QString
&
url
)
{
{
s
ourceURL
=
url
;
mS
ourceURL
=
url
;
}
}
uchar
*
uchar
*
WebImage
::
getImageData
(
void
)
const
WebImage
::
getImageData
(
void
)
const
{
{
return
i
mage
->
scanLine
(
0
);
return
mI
mage
->
scanLine
(
0
);
}
}
bool
bool
WebImage
::
setData
(
const
QByteArray
&
data
)
WebImage
::
setData
(
const
QByteArray
&
data
)
{
{
QImage
tempImage
;
QImage
tempImage
;
if
(
tempImage
.
loadFromData
(
data
))
{
if
(
tempImage
.
loadFromData
(
data
))
if
(
image
.
isNull
())
{
{
image
.
reset
(
new
QImage
);
if
(
mImage
.
isNull
())
{
mImage
.
reset
(
new
QImage
);
}
}
*
i
mage
=
QGLWidget
::
convertToGLFormat
(
tempImage
);
*
mI
mage
=
QGLWidget
::
convertToGLFormat
(
tempImage
);
return
true
;
return
true
;
}
else
{
}
else
{
return
false
;
return
false
;
}
}
}
}
...
@@ -103,14 +107,18 @@ bool
...
@@ -103,14 +107,18 @@ bool
WebImage
::
setData
(
const
QString
&
filename
)
WebImage
::
setData
(
const
QString
&
filename
)
{
{
QImage
tempImage
;
QImage
tempImage
;
if
(
tempImage
.
load
(
filename
))
{
if
(
tempImage
.
load
(
filename
))
if
(
image
.
isNull
())
{
{
image
.
reset
(
new
QImage
);
if
(
mImage
.
isNull
())
{
mImage
.
reset
(
new
QImage
);
}
}
*
i
mage
=
QGLWidget
::
convertToGLFormat
(
tempImage
);
*
mI
mage
=
QGLWidget
::
convertToGLFormat
(
tempImage
);
return
true
;
return
true
;
}
else
{
}
else
{
return
false
;
return
false
;
}
}
}
}
...
@@ -118,41 +126,41 @@ WebImage::setData(const QString& filename)
...
@@ -118,41 +126,41 @@ WebImage::setData(const QString& filename)
int
int
WebImage
::
getWidth
(
void
)
const
WebImage
::
getWidth
(
void
)
const
{
{
return
i
mage
->
width
();
return
mI
mage
->
width
();
}
}
int
int
WebImage
::
getHeight
(
void
)
const
WebImage
::
getHeight
(
void
)
const
{
{
return
i
mage
->
height
();
return
mI
mage
->
height
();
}
}
int
int
WebImage
::
getByteCount
(
void
)
const
WebImage
::
getByteCount
(
void
)
const
{
{
return
i
mage
->
byteCount
();
return
mI
mage
->
byteCount
();
}
}
ulong
quint64
WebImage
::
getLastReference
(
void
)
const
WebImage
::
getLastReference
(
void
)
const
{
{
return
l
astReference
;
return
mL
astReference
;
}
}
void
void
WebImage
::
setLastReference
(
ulong
value
)
WebImage
::
setLastReference
(
quint64
value
)
{
{
l
astReference
=
value
;
mL
astReference
=
value
;
}
}
bool
bool
WebImage
::
getSyncFlag
(
void
)
const
WebImage
::
getSyncFlag
(
void
)
const
{
{
return
s
yncFlag
;
return
mS
yncFlag
;
}
}
void
void
WebImage
::
setSyncFlag
(
bool
onoff
)
WebImage
::
setSyncFlag
(
bool
onoff
)
{
{
s
yncFlag
=
onoff
;
mS
yncFlag
=
onoff
;
}
}
src/ui/map3D/WebImage.h
View file @
db075953
...
@@ -64,18 +64,18 @@ public:
...
@@ -64,18 +64,18 @@ public:
int
getHeight
(
void
)
const
;
int
getHeight
(
void
)
const
;
int
getByteCount
(
void
)
const
;
int
getByteCount
(
void
)
const
;
ulong
getLastReference
(
void
)
const
;
quint64
getLastReference
(
void
)
const
;
void
setLastReference
(
ulong
value
);
void
setLastReference
(
quint64
value
);
bool
getSyncFlag
(
void
)
const
;
bool
getSyncFlag
(
void
)
const
;
void
setSyncFlag
(
bool
onoff
);
void
setSyncFlag
(
bool
onoff
);
private:
private:
State
s
tate
;
State
mS
tate
;
QString
s
ourceURL
;
QString
mS
ourceURL
;
QScopedPointer
<
QImage
>
i
mage
;
QScopedPointer
<
QImage
>
mI
mage
;
ulong
l
astReference
;
quint64
mL
astReference
;
bool
s
yncFlag
;
bool
mS
yncFlag
;
};
};
typedef
QSharedPointer
<
WebImage
>
WebImagePtr
;
typedef
QSharedPointer
<
WebImage
>
WebImagePtr
;
...
...
src/ui/map3D/WebImageCache.cc
View file @
db075953
...
@@ -25,102 +25,129 @@ This file is part of the QGROUNDCONTROL project
...
@@ -25,102 +25,129 @@ This file is part of the QGROUNDCONTROL project
* @file
* @file
* @brief Definition of the class WebImageCache.
* @brief Definition of the class WebImageCache.
*
*
* @author Lionel Heng <hengli@
student
.ethz.ch>
* @author Lionel Heng <hengli@
inf
.ethz.ch>
*
*
*/
*/
#include "WebImageCache.h"
#include "WebImageCache.h"
#include <cstdio>
#include <QNetworkReply>
#include <QNetworkReply>
#include <QPixmap>
#include <QPixmap>
WebImageCache
::
WebImageCache
(
QObject
*
parent
,
uint32_t
_
cacheSize
)
WebImageCache
::
WebImageCache
(
QObject
*
parent
,
int
cacheSize
)
:
QObject
(
parent
)
:
QObject
(
parent
)
,
cacheSize
(
_
cacheSize
)
,
mCacheSize
(
cacheSize
)
,
c
urrentReference
(
0
)
,
mC
urrentReference
(
0
)
,
n
etworkManager
(
new
QNetworkAccessManager
)
,
mN
etworkManager
(
new
QNetworkAccessManager
)
{
{
for
(
uint32_t
i
=
0
;
i
<
cacheSize
;
++
i
)
{
for
(
int
i
=
0
;
i
<
mCacheSize
;
++
i
)
{
WebImagePtr
image
(
new
WebImage
);
WebImagePtr
image
(
new
WebImage
);
w
ebImages
.
push_back
(
image
);
mW
ebImages
.
push_back
(
image
);
}
}
connect
(
n
etworkManager
.
data
(),
SIGNAL
(
finished
(
QNetworkReply
*
)),
connect
(
mN
etworkManager
.
data
(),
SIGNAL
(
finished
(
QNetworkReply
*
)),
this
,
SLOT
(
downloadFinished
(
QNetworkReply
*
)));
this
,
SLOT
(
downloadFinished
(
QNetworkReply
*
)));
}
}
QPair
<
WebImagePtr
,
int
32_t
>
QPair
<
WebImagePtr
,
int
>
WebImageCache
::
lookup
(
const
QString
&
url
)
WebImageCache
::
lookup
(
const
QString
&
url
)
{
{
QPair
<
WebImagePtr
,
int
32_t
>
cacheEntry
;
QPair
<
WebImagePtr
,
int
>
cacheEntry
;
for
(
int32_t
i
=
0
;
i
<
webImages
.
size
();
++
i
)
{
for
(
int
i
=
0
;
i
<
mWebImages
.
size
();
++
i
)
if
(
webImages
[
i
]
->
getState
()
!=
WebImage
::
UNINITIALIZED
&&
{
webImages
[
i
]
->
getSourceURL
()
==
url
)
{
WebImagePtr
&
image
=
mWebImages
[
i
];
cacheEntry
.
first
=
webImages
[
i
];
if
(
image
->
getState
()
!=
WebImage
::
UNINITIALIZED
&&
image
->
getSourceURL
()
==
url
)
{
cacheEntry
.
first
=
image
;
cacheEntry
.
second
=
i
;
cacheEntry
.
second
=
i
;
break
;
break
;
}
}
}
}
if
(
cacheEntry
.
first
.
isNull
())
{
if
(
cacheEntry
.
first
.
isNull
())
for
(
int32_t
i
=
0
;
i
<
webImages
.
size
();
++
i
)
{
{
for
(
int
i
=
0
;
i
<
mWebImages
.
size
();
++
i
)
{
WebImagePtr
&
image
=
mWebImages
[
i
];
// get uninitialized image
// get uninitialized image
if
(
webImages
[
i
]
->
getState
()
==
WebImage
::
UNINITIALIZED
)
{
if
(
image
->
getState
()
==
WebImage
::
UNINITIALIZED
)
cacheEntry
.
first
=
webImages
[
i
];
{
cacheEntry
.
first
=
image
;
cacheEntry
.
second
=
i
;
cacheEntry
.
second
=
i
;
break
;
break
;
}
}
// get oldest image
// get oldest image
else
if
(
webImages
[
i
]
->
getState
()
==
WebImage
::
READY
&&
else
if
(
image
->
getState
()
==
WebImage
::
READY
&&
(
cacheEntry
.
first
.
isNull
()
||
(
cacheEntry
.
first
.
isNull
()
||
webImages
[
i
]
->
getLastReference
()
<
image
->
getLastReference
()
<
cacheEntry
.
first
->
getLastReference
()))
{
cacheEntry
.
first
->
getLastReference
()))
cacheEntry
.
first
=
webImages
[
i
];
{
cacheEntry
.
first
=
image
;
cacheEntry
.
second
=
i
;
cacheEntry
.
second
=
i
;
}
}
}
}
if
(
cacheEntry
.
first
.
isNull
())
{
if
(
cacheEntry
.
first
.
isNull
())
return
qMakePair
(
WebImagePtr
(),
-
1
);
{
}
else
{
return
qMakePair
(
WebImagePtr
(),
-
1
);
if
(
cacheEntry
.
first
->
getState
()
==
WebImage
::
READY
)
{
}
else
{
if
(
cacheEntry
.
first
->
getState
()
==
WebImage
::
READY
)
{
cacheEntry
.
first
->
clear
();
cacheEntry
.
first
->
clear
();
}
}
cacheEntry
.
first
->
setSourceURL
(
url
);
cacheEntry
.
first
->
setSourceURL
(
url
);
cacheEntry
.
first
->
setLastReference
(
c
urrentReference
);
cacheEntry
.
first
->
setLastReference
(
mC
urrentReference
);
++
c
urrentReference
;
++
mC
urrentReference
;
cacheEntry
.
first
->
setState
(
WebImage
::
REQUESTED
);
cacheEntry
.
first
->
setState
(
WebImage
::
REQUESTED
);
if
(
url
.
left
(
4
).
compare
(
"http"
)
==
0
)
{
if
(
url
.
left
(
4
).
compare
(
"http"
)
==
0
)
networkManager
->
get
(
QNetworkRequest
(
QUrl
(
url
)));
{
}
else
{
mNetworkManager
->
get
(
QNetworkRequest
(
QUrl
(
url
)));
if
(
cacheEntry
.
first
->
setData
(
url
))
{
}
else
{
if
(
cacheEntry
.
first
->
setData
(
url
))
{
cacheEntry
.
first
->
setSyncFlag
(
true
);
cacheEntry
.
first
->
setSyncFlag
(
true
);
cacheEntry
.
first
->
setState
(
WebImage
::
READY
);
cacheEntry
.
first
->
setState
(
WebImage
::
READY
);
}
else
{
}
else
{
cacheEntry
.
first
->
setState
(
WebImage
::
UNINITIALIZED
);
cacheEntry
.
first
->
setState
(
WebImage
::
UNINITIALIZED
);
}
}
}
}
return
cacheEntry
;
return
cacheEntry
;
}
}
}
else
{
}
if
(
cacheEntry
.
first
->
getState
()
==
WebImage
::
READY
)
{
else
cacheEntry
.
first
->
setLastReference
(
currentReference
);
{
++
currentReference
;
if
(
cacheEntry
.
first
->
getState
()
==
WebImage
::
READY
)
{
cacheEntry
.
first
->
setLastReference
(
mCurrentReference
);
++
mCurrentReference
;
return
cacheEntry
;
return
cacheEntry
;
}
else
{
}
else
{
return
qMakePair
(
WebImagePtr
(),
-
1
);
return
qMakePair
(
WebImagePtr
(),
-
1
);
}
}
}
}
}
}
WebImagePtr
WebImagePtr
WebImageCache
::
at
(
int
32_t
index
)
const
WebImageCache
::
at
(
int
index
)
const
{
{
return
w
ebImages
[
index
];
return
mW
ebImages
[
index
];
}
}
void
void
...
@@ -128,17 +155,21 @@ WebImageCache::downloadFinished(QNetworkReply* reply)
...
@@ -128,17 +155,21 @@ WebImageCache::downloadFinished(QNetworkReply* reply)
{
{
reply
->
deleteLater
();
reply
->
deleteLater
();
if
(
reply
->
error
()
!=
QNetworkReply
::
NoError
)
{
if
(
reply
->
error
()
!=
QNetworkReply
::
NoError
)
{
return
;
return
;
}
}
QVariant
attribute
=
reply
->
attribute
(
QNetworkRequest
::
RedirectionTargetAttribute
);
QVariant
attribute
=
reply
->
attribute
(
QNetworkRequest
::
RedirectionTargetAttribute
);
if
(
attribute
.
isValid
())
{
if
(
attribute
.
isValid
())
{
return
;
return
;
}
}
WebImagePtr
image
;
WebImagePtr
image
;
foreach
(
image
,
webImages
)
{
foreach
(
image
,
mWebImages
)
if
(
reply
->
url
().
toString
()
==
image
->
getSourceURL
())
{
{
if
(
reply
->
url
().
toString
()
==
image
->
getSourceURL
())
{
image
->
setData
(
reply
->
readAll
());
image
->
setData
(
reply
->
readAll
());
image
->
setSyncFlag
(
true
);
image
->
setSyncFlag
(
true
);
image
->
setState
(
WebImage
::
READY
);
image
->
setState
(
WebImage
::
READY
);
...
...
src/ui/map3D/WebImageCache.h
View file @
db075953
...
@@ -25,7 +25,7 @@ This file is part of the QGROUNDCONTROL project
...
@@ -25,7 +25,7 @@ This file is part of the QGROUNDCONTROL project
* @file
* @file
* @brief Definition of the class WebImageCache.
* @brief Definition of the class WebImageCache.
*
*
* @author Lionel Heng <hengli@
student
.ethz.ch>
* @author Lionel Heng <hengli@
inf
.ethz.ch>
*
*
*/
*/
...
@@ -43,22 +43,22 @@ class WebImageCache : public QObject
...
@@ -43,22 +43,22 @@ class WebImageCache : public QObject
Q_OBJECT
Q_OBJECT
public:
public:
WebImageCache
(
QObject
*
parent
,
uint32_
t
cacheSize
);
WebImageCache
(
QObject
*
parent
,
in
t
cacheSize
);
QPair
<
WebImagePtr
,
int
32_t
>
lookup
(
const
QString
&
url
);
QPair
<
WebImagePtr
,
int
>
lookup
(
const
QString
&
url
);
WebImagePtr
at
(
int
32_t
index
)
const
;
WebImagePtr
at
(
int
index
)
const
;
private
Q_SLOTS
:
private
Q_SLOTS
:
void
downloadFinished
(
QNetworkReply
*
reply
);
void
downloadFinished
(
QNetworkReply
*
reply
);
private:
private:
uint32_t
c
acheSize
;
int
mC
acheSize
;
QVector
<
WebImagePtr
>
w
ebImages
;
QVector
<
WebImagePtr
>
mW
ebImages
;
uint64_t
c
urrentReference
;
quint64
mC
urrentReference
;
QScopedPointer
<
QNetworkAccessManager
>
n
etworkManager
;
QScopedPointer
<
QNetworkAccessManager
>
mN
etworkManager
;
};
};
#endif // WEBIMAGECACHE_H
#endif // WEBIMAGECACHE_H
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