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
ee74c2c3
Commit
ee74c2c3
authored
Feb 25, 2012
by
Lionel Heng
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Made imagery feature working again in 3D view.
parent
6b5c1e50
Changes
13
Show whitespace changes
Inline
Side-by-side
Showing
13 changed files
with
480 additions
and
110 deletions
+480
-110
qgroundcontrol.pro
qgroundcontrol.pro
+5
-3
GlobalViewParams.cc
src/ui/map3D/GlobalViewParams.cc
+30
-6
GlobalViewParams.h
src/ui/map3D/GlobalViewParams.h
+11
-1
Imagery.cc
src/ui/map3D/Imagery.cc
+115
-66
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
+67
-15
Pixhawk3DWidget.h
src/ui/map3D/Pixhawk3DWidget.h
+4
-2
SystemContainer.cc
src/ui/map3D/SystemContainer.cc
+6
-0
SystemContainer.h
src/ui/map3D/SystemContainer.h
+4
-0
ViewParamWidget.cc
src/ui/map3D/ViewParamWidget.cc
+15
-8
ViewParamWidget.h
src/ui/map3D/ViewParamWidget.h
+1
-0
No files found.
qgroundcontrol.pro
View file @
ee74c2c3
...
...
@@ -391,7 +391,8 @@ contains(DEPENDENCIES_PRESENT, osg) {
src
/
ui
/
map3D
/
Imagery
.
h
\
src
/
ui
/
map3D
/
HUDScaleGeode
.
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
)
{
message
(
"Including headers for Protocol Buffers"
)
...
...
@@ -535,7 +536,8 @@ contains(DEPENDENCIES_PRESENT, osg) {
src
/
ui
/
map3D
/
Imagery
.
cc
\
src
/
ui
/
map3D
/
HUDScaleGeode
.
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
)
{
message
(
"Including sources for osgEarth"
)
...
...
src/ui/map3D/GlobalViewParams.cc
View file @
ee74c2c3
...
...
@@ -36,6 +36,30 @@ GlobalViewParams::displayWorldGrid(void) const
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
&
GlobalViewParams
::
imageryType
(
void
)
{
...
...
@@ -72,6 +96,12 @@ GlobalViewParams::frame(void) const
return
mFrame
;
}
void
GlobalViewParams
::
signalImageryParamsChanged
(
void
)
{
emit
imageryParamsChanged
();
}
QVector3D
&
GlobalViewParams
::
terrainPositionOffset
(
void
)
{
...
...
@@ -132,12 +162,6 @@ GlobalViewParams::frameChanged(const QString& text)
}
}
void
GlobalViewParams
::
imageryTypeChanged
(
int
index
)
{
mImageryType
=
static_cast
<
Imagery
::
Type
>
(
index
);
}
void
GlobalViewParams
::
toggleWorldGrid
(
int
state
)
{
...
...
src/ui/map3D/GlobalViewParams.h
View file @
ee74c2c3
...
...
@@ -21,6 +21,12 @@ public:
bool
&
displayWorldGrid
(
void
);
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
)
const
;
...
...
@@ -30,6 +36,8 @@ public:
MAV_FRAME
&
frame
(
void
);
MAV_FRAME
frame
(
void
)
const
;
void
signalImageryParamsChanged
(
void
);
QVector3D
&
terrainPositionOffset
(
void
);
QVector3D
terrainPositionOffset
(
void
)
const
;
...
...
@@ -39,16 +47,18 @@ public:
public
slots
:
void
followCameraChanged
(
const
QString
&
text
);
void
frameChanged
(
const
QString
&
text
);
void
imageryTypeChanged
(
int
index
);
void
toggleTerrain
(
int
state
);
void
toggleWorldGrid
(
int
state
);
signals:
void
followCameraChanged
(
int
systemId
);
void
imageryParamsChanged
(
void
);
private:
bool
mDisplayTerrain
;
bool
mDisplayWorldGrid
;
QVector3D
mImageryOffset
;
QString
mImageryPath
;
Imagery
::
Type
mImageryType
;
int
mFollowCameraId
;
MAV_FRAME
mFrame
;
...
...
src/ui/map3D/Imagery.cc
View file @
ee74c2c3
...
...
@@ -32,6 +32,7 @@ This file is part of the QGROUNDCONTROL project
#include "Imagery.h"
#include <cmath>
#include <cstdio>
#include <iomanip>
#include <sstream>
...
...
@@ -41,7 +42,11 @@ const double WGS84_ECCSQ = 0.00669437999013;
const
int
MAX_ZOOM_LEVEL
=
20
;
Imagery
::
Imagery
()
:
textureCache
(
new
TextureCache
(
1000
))
:
mTextureCache
(
new
TextureCache
(
500
))
,
mImageryType
(
Imagery
::
BLANK_MAP
)
,
mXOffset
(
0.0
)
,
mYOffset
(
0.0
)
,
mZOffset
(
0.0
)
{
}
...
...
@@ -49,20 +54,27 @@ Imagery::Imagery()
Imagery
::
Type
Imagery
::
getImageryType
(
void
)
const
{
return
current
ImageryType
;
return
m
ImageryType
;
}
void
Imagery
::
setImageryType
(
Imagery
::
Type
type
)
{
current
ImageryType
=
type
;
m
ImageryType
=
type
;
}
void
Imagery
::
setOffset
(
double
xOffset
,
double
yOffset
)
Imagery
::
setOffset
(
double
xOffset
,
double
yOffset
,
double
zOffset
)
{
this
->
xOffset
=
xOffset
;
this
->
yOffset
=
yOffset
;
mXOffset
=
xOffset
;
mYOffset
=
yOffset
;
mZOffset
=
zOffset
;
}
void
Imagery
::
setPath
(
const
QString
&
path
)
{
mImageryPath
=
path
.
toStdString
();
}
void
...
...
@@ -70,21 +82,27 @@ Imagery::prefetch2D(double windowWidth, double windowHeight,
double
zoom
,
double
xOrigin
,
double
yOrigin
,
const
QString
&
utmZone
)
{
if
(
currentImageryType
==
BLANK_MAP
)
{
if
(
mImageryType
==
BLANK_MAP
)
{
return
;
}
double
tileResolution
=
1.0
;
if
(
currentImageryType
==
GOOGLE_SATELLITE
||
currentImageryType
==
GOOGLE_MAP
)
{
if
(
mImageryType
==
GOOGLE_SATELLITE
||
mImageryType
==
GOOGLE_MAP
)
{
tileResolution
=
1.0
;
while
(
tileResolution
*
3.0
/
2.0
<
1.0
/
zoom
)
{
while
(
tileResolution
*
3.0
/
2.0
<
1.0
/
zoom
)
{
tileResolution
*=
2.0
;
}
if
(
tileResolution
>
512.0
)
{
if
(
tileResolution
>
512.0
)
{
tileResolution
=
512.0
;
}
}
else
if
(
currentImageryType
==
SWISSTOPO_SATELLITE
)
{
}
else
if
(
mImageryType
==
OFFLINE_SATELLITE
)
{
tileResolution
=
0.25
;
}
...
...
@@ -98,11 +116,13 @@ Imagery::prefetch2D(double windowWidth, double windowHeight,
yOrigin
+
windowHeight
/
2.0
/
zoom
*
1.5
,
utmZone
,
minTileX
,
minTileY
,
maxTileX
,
maxTileY
,
zoomLevel
);
for
(
int
r
=
minTileY
;
r
<=
maxTileY
;
++
r
)
{
for
(
int
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
for
(
int
r
=
minTileY
;
r
<=
maxTileY
;
++
r
)
{
for
(
int
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
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,
void
Imagery
::
draw2D
(
double
windowWidth
,
double
windowHeight
,
double
zoom
,
double
xOrigin
,
double
yOrigin
,
double
xOffset
,
double
yOffset
,
double
zOffset
,
const
QString
&
utmZone
)
{
if
(
getNumDrawables
()
>
0
)
{
if
(
getNumDrawables
()
>
0
)
{
removeDrawables
(
0
,
getNumDrawables
());
}
if
(
currentImageryType
==
BLANK_MAP
)
{
if
(
mImageryType
==
BLANK_MAP
)
{
return
;
}
double
tileResolution
=
1.0
;
if
(
currentImageryType
==
GOOGLE_SATELLITE
||
currentImageryType
==
GOOGLE_MAP
)
{
if
(
mImageryType
==
GOOGLE_SATELLITE
||
mImageryType
==
GOOGLE_MAP
)
{
tileResolution
=
1.0
;
while
(
tileResolution
*
3.0
/
2.0
<
1.0
/
zoom
)
{
while
(
tileResolution
*
3.0
/
2.0
<
1.0
/
zoom
)
{
tileResolution
*=
2.0
;
}
if
(
tileResolution
>
512.0
)
{
if
(
tileResolution
>
512.0
)
{
tileResolution
=
512.0
;
}
}
else
if
(
currentImageryType
==
SWISSTOPO_SATELLITE
)
{
}
else
if
(
mImageryType
==
OFFLINE_SATELLITE
)
{
tileResolution
=
0.25
;
}
...
...
@@ -145,20 +171,23 @@ Imagery::draw2D(double windowWidth, double windowHeight,
yOrigin
+
windowHeight
/
2.0
/
zoom
*
1.5
,
utmZone
,
minTileX
,
minTileY
,
maxTileX
,
maxTileY
,
zoomLevel
);
for
(
int
r
=
minTileY
;
r
<=
maxTileY
;
++
r
)
{
for
(
int
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
for
(
int
r
=
minTileY
;
r
<=
maxTileY
;
++
r
)
{
for
(
int
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
QString
tileURL
=
getTileLocation
(
c
,
r
,
zoomLevel
,
tileResolution
);
double
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
);
if
(
!
t
.
isNull
())
{
addDrawable
(
t
->
draw
(
y1
-
yOffset
,
x1
-
xOffset
,
y2
-
yOffset
,
x2
-
xOffset
,
y3
-
yOffset
,
x3
-
xOffset
,
y4
-
yOffset
,
x4
-
xOffset
,
zOffset
,
TexturePtr
t
=
mTextureCache
->
get
(
tileURL
);
if
(
!
t
.
isNull
())
{
addDrawable
(
t
->
draw
(
y1
,
x1
,
y2
,
x2
,
y3
,
x3
,
y4
,
x4
,
-
mZOffset
,
true
));
}
}
...
...
@@ -170,7 +199,8 @@ Imagery::prefetch3D(double radius, double tileResolution,
double
xOrigin
,
double
yOrigin
,
const
QString
&
utmZone
)
{
if
(
currentImageryType
==
BLANK_MAP
)
{
if
(
mImageryType
==
BLANK_MAP
)
{
return
;
}
...
...
@@ -178,15 +208,17 @@ Imagery::prefetch3D(double radius, double tileResolution,
int
zoomLevel
;
tileBounds
(
tileResolution
,
xOrigin
-
radius
,
yOrigin
-
radius
,
xOrigin
+
radius
,
yOrigin
+
radius
,
utmZone
,
xOrigin
+
mXOffset
-
radius
,
yOrigin
+
mYOffset
-
radius
,
xOrigin
+
mXOffset
+
radius
,
yOrigin
+
mYOffset
+
radius
,
utmZone
,
minTileX
,
minTileY
,
maxTileX
,
maxTileY
,
zoomLevel
);
for
(
int
r
=
minTileY
;
r
<=
maxTileY
;
++
r
)
{
for
(
int
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
for
(
int
r
=
minTileY
;
r
<=
maxTileY
;
++
r
)
{
for
(
int
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
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,
void
Imagery
::
draw3D
(
double
radius
,
double
tileResolution
,
double
xOrigin
,
double
yOrigin
,
double
xOffset
,
double
yOffset
,
double
zOffset
,
double
xOffset
,
double
yOffset
,
const
QString
&
utmZone
)
{
if
(
getNumDrawables
()
>
0
)
{
if
(
getNumDrawables
()
>
0
)
{
removeDrawables
(
0
,
getNumDrawables
());
}
if
(
currentImageryType
==
BLANK_MAP
)
{
if
(
mImageryType
==
BLANK_MAP
)
{
return
;
}
...
...
@@ -209,25 +243,28 @@ Imagery::draw3D(double radius, double tileResolution,
int
zoomLevel
;
tileBounds
(
tileResolution
,
xOrigin
-
radius
,
yOrigin
-
radius
,
xOrigin
+
radius
,
yOrigin
+
radius
,
utmZone
,
xOrigin
+
mXOffset
-
radius
,
yOrigin
+
mYOffset
-
radius
,
xOrigin
+
mXOffset
+
radius
,
yOrigin
+
mYOffset
+
radius
,
utmZone
,
minTileX
,
minTileY
,
maxTileX
,
maxTileY
,
zoomLevel
);
for
(
int
r
=
minTileY
;
r
<=
maxTileY
;
++
r
)
{
for
(
int
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
for
(
int
r
=
minTileY
;
r
<=
maxTileY
;
++
r
)
{
for
(
int
c
=
minTileX
;
c
<=
maxTileX
;
++
c
)
{
QString
tileURL
=
getTileLocation
(
c
,
r
,
zoomLevel
,
tileResolution
);
double
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
())
{
addDrawable
(
t
->
draw
(
y1
-
yOffset
,
x1
-
xOffset
,
y2
-
yOffset
,
x2
-
xOffset
,
y3
-
yOffset
,
x3
-
xOffset
,
y4
-
yOffset
,
x4
-
xOffset
,
zOffset
,
if
(
!
t
.
isNull
())
{
addDrawable
(
t
->
draw
(
y1
-
mYOffset
+
yOffset
,
x1
-
mXOffset
+
xOffset
,
y2
-
mYOffset
+
yOffset
,
x2
-
mXOffset
+
xOffset
,
y3
-
mYOffset
+
yOffset
,
x3
-
mXOffset
+
xOffset
,
y4
-
mYOffset
+
yOffset
,
x4
-
mXOffset
+
xOffset
,
-
mZOffset
,
true
));
}
}
...
...
@@ -237,7 +274,7 @@ Imagery::draw3D(double radius, double tileResolution,
bool
Imagery
::
update
(
void
)
{
t
extureCache
->
sync
();
mT
extureCache
->
sync
();
return
true
;
}
...
...
@@ -247,8 +284,9 @@ Imagery::imageBounds(int tileX, int tileY, double tileResolution,
double
&
x1
,
double
&
y1
,
double
&
x2
,
double
&
y2
,
double
&
x3
,
double
&
y3
,
double
&
x4
,
double
&
y4
)
const
{
if
(
currentImageryType
==
GOOGLE_MAP
||
currentImageryType
==
GOOGLE_SATELLITE
)
{
if
(
mImageryType
==
GOOGLE_MAP
||
mImageryType
==
GOOGLE_SATELLITE
)
{
int
zoomLevel
=
MAX_ZOOM_LEVEL
-
static_cast
<
int
>
(
rint
(
log2
(
tileResolution
)));
int
numTiles
=
static_cast
<
int
>
(
exp2
(
static_cast
<
double
>
(
zoomLevel
)));
...
...
@@ -263,7 +301,9 @@ Imagery::imageBounds(int tileX, int tileY, double tileResolution,
LLtoUTM
(
lat1
,
lon2
,
x2
,
y2
,
utmZone
);
LLtoUTM
(
lat2
,
lon2
,
x3
,
y3
,
utmZone
);
LLtoUTM
(
lat2
,
lon1
,
x4
,
y4
,
utmZone
);
}
else
if
(
currentImageryType
==
SWISSTOPO_SATELLITE
)
{
}
else
if
(
mImageryType
==
OFFLINE_SATELLITE
)
{
double
utmMultiplier
=
tileResolution
*
200.0
;
double
minX
=
tileX
*
utmMultiplier
;
double
maxX
=
minX
+
utmMultiplier
;
...
...
@@ -293,15 +333,18 @@ Imagery::tileBounds(double tileResolution,
double
centerUtmY
=
(
maxUtmY
-
minUtmY
)
/
2.0
+
minUtmY
;
int
centerTileX
,
centerTileY
;
if
(
currentImageryType
==
GOOGLE_MAP
||
currentImageryType
==
GOOGLE_SATELLITE
)
{
if
(
mImageryType
==
GOOGLE_MAP
||
mImageryType
==
GOOGLE_SATELLITE
)
{
UTMtoTile
(
minUtmX
,
minUtmY
,
utmZone
,
tileResolution
,
minTileX
,
maxTileY
,
zoomLevel
);
UTMtoTile
(
centerUtmX
,
centerUtmY
,
utmZone
,
tileResolution
,
centerTileX
,
centerTileY
,
zoomLevel
);
UTMtoTile
(
maxUtmX
,
maxUtmY
,
utmZone
,
tileResolution
,
maxTileX
,
minTileY
,
zoomLevel
);
}
else
if
(
currentImageryType
==
SWISSTOPO_SATELLITE
)
{
}
else
if
(
mImageryType
==
OFFLINE_SATELLITE
)
{
double
utmMultiplier
=
tileResolution
*
200
;
minTileX
=
static_cast
<
int
>
(
rint
(
minUtmX
/
utmMultiplier
));
...
...
@@ -312,11 +355,13 @@ Imagery::tileBounds(double tileResolution,
maxTileY
=
static_cast
<
int
>
(
rint
(
maxUtmY
/
utmMultiplier
));
}
if
(
maxTileX
-
minTileX
+
1
>
14
)
{
if
(
maxTileX
-
minTileX
+
1
>
14
)
{
minTileX
=
centerTileX
-
7
;
maxTileX
=
centerTileX
+
6
;
}
if
(
maxTileY
-
minTileY
+
1
>
14
)
{
if
(
maxTileY
-
minTileY
+
1
>
14
)
{
minTileY
=
centerTileY
-
7
;
maxTileY
=
centerTileY
+
6
;
}
...
...
@@ -558,7 +603,8 @@ Imagery::getTileLocation(int tileX, int tileY, int zoomLevel,
{
std
::
ostringstream
oss
;
switch
(
currentImageryType
)
{
switch
(
mImageryType
)
{
case
GOOGLE_MAP
:
oss
<<
"http://mt0.google.com/vt/lyrs=m@120&x="
<<
tileX
<<
"&y="
<<
tileY
<<
"&z="
<<
zoomLevel
;
...
...
@@ -567,12 +613,15 @@ Imagery::getTileLocation(int tileX, int tileY, int zoomLevel,
oss
<<
"http://khm.google.com/vt/lbw/lyrs=y&x="
<<
tileX
<<
"&y="
<<
tileY
<<
"&z="
<<
zoomLevel
;
break
;
case
SWISSTOPO
_SATELLITE
:
oss
<<
"../map/eth_zurich_swissimage_025
/200/color/"
<<
tileY
case
OFFLINE
_SATELLITE
:
oss
<<
mImageryPath
<<
"
/200/color/"
<<
tileY
<<
"/tile-"
;
if
(
tileResolution
<
1.0
)
{
if
(
tileResolution
<
1.0
)
{
oss
<<
std
::
fixed
<<
std
::
setprecision
(
2
)
<<
tileResolution
;
}
else
{
}
else
{
oss
<<
static_cast
<
int
>
(
rint
(
tileResolution
));
}
oss
<<
"-"
<<
tileY
<<
"-"
<<
tileX
<<
".jpg"
;
...
...
src/ui/map3D/Imagery.h
View file @
ee74c2c3
...
...
@@ -41,25 +41,26 @@ This file is part of the QGROUNDCONTROL project
class
Imagery
:
public
osg
::
Geode
{
public:
enum
Type
{
enum
Type
{
BLANK_MAP
=
0
,
GOOGLE_MAP
=
1
,
GOOGLE_SATELLITE
=
2
,
SWISSTOPO
_SATELLITE
=
3
OFFLINE
_SATELLITE
=
3
};
Imagery
();
Type
getImageryType
(
void
)
const
;
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
,
double
zoom
,
double
xOrigin
,
double
yOrigin
,
const
QString
&
utmZone
);
void
draw2D
(
double
windowWidth
,
double
windowHeight
,
double
zoom
,
double
xOrigin
,
double
yOrigin
,
double
xOffset
,
double
yOffset
,
double
zOffset
,
const
QString
&
utmZone
);
void
prefetch3D
(
double
radius
,
double
tileResolution
,
...
...
@@ -67,7 +68,7 @@ public:
const
QString
&
utmZone
);
void
draw3D
(
double
radius
,
double
tileResolution
,
double
xOrigin
,
double
yOrigin
,
double
xOffset
,
double
yOffset
,
double
zOffset
,
double
xOffset
,
double
yOffset
,
const
QString
&
utmZone
);
bool
update
(
void
);
...
...
@@ -102,12 +103,14 @@ private:
QString
getTileLocation
(
int
tileX
,
int
tileY
,
int
zoomLevel
,
double
tileResolution
)
const
;
QScopedPointer
<
TextureCache
>
t
extureCache
;
QScopedPointer
<
TextureCache
>
mT
extureCache
;
Type
currentImageryType
;
Type
mImageryType
;
std
::
string
mImageryPath
;
double
xOffset
;
double
yOffset
;
double
mXOffset
;
double
mYOffset
;
double
mZOffset
;
};
#endif // IMAGERY_H
src/ui/map3D/ImageryParamDialog.cc
0 → 100644
View file @
ee74c2c3
#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 @
ee74c2c3
#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 @
ee74c2c3
...
...
@@ -91,6 +91,8 @@ Pixhawk3DWidget::Pixhawk3DWidget(QWidget* parent)
this
,
SLOT
(
systemCreated
(
UASInterface
*
)));
connect
(
mGlobalViewParams
.
data
(),
SIGNAL
(
followCameraChanged
(
int
)),
this
,
SLOT
(
followCameraChanged
(
int
)));
connect
(
mGlobalViewParams
.
data
(),
SIGNAL
(
imageryParamsChanged
(
void
)),
this
,
SLOT
(
imageryParamsChanged
(
void
)));
MainWindow
*
parentWindow
=
qobject_cast
<
MainWindow
*>
(
parent
);
parentWindow
->
addDockWidget
(
Qt
::
LeftDockWidgetArea
,
mViewParamWidget
);
...
...
@@ -139,11 +141,14 @@ Pixhawk3DWidget::systemCreated(UASInterface *uas)
this
,
SLOT
(
attitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
userPositionSetPointsChanged
(
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)
connect
(
uas
,
SIGNAL
(
overlayChanged
(
UASInterface
*
)),
this
,
SLOT
(
addOverlay
(
UASInterface
*
)));
#endif
// mSystemContainerMap[systemId].gpsLocalOrigin() = QVector3D(47.419182, 8.566980, 428);
initializeSystem
(
systemId
,
uas
->
getColor
());
emit
systemCreatedSignal
(
uas
);
...
...
@@ -333,6 +338,20 @@ Pixhawk3DWidget::attitudeChanged(UASInterface* uas,
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
Pixhawk3DWidget
::
setpointChanged
(
int
uasId
,
float
x
,
float
y
,
float
z
,
float
yaw
)
...
...
@@ -465,6 +484,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
Pixhawk3DWidget
::
recenterActiveCamera
(
void
)
{
...
...
@@ -981,8 +1010,6 @@ Pixhawk3DWidget::update(void)
#endif
}
mImageryNode
->
setImageryType
(
mGlobalViewParams
->
imageryType
());
if
(
mFollowCameraId
!=
-
1
)
{
UASInterface
*
uas
=
UASManager
::
instance
()
->
getUASForId
(
mFollowCameraId
);
...
...
@@ -1091,13 +1118,27 @@ Pixhawk3DWidget::update(void)
updateRGBD
(
uas
,
frame
,
systemData
.
rgbImageNode
(),
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
}
if
(
frame
==
MAV_FRAME_GLOBAL
&&
mGlobalViewParams
->
imageryType
()
!=
Imagery
::
BLANK_MAP
)
{
// updateImagery(
robotX, robotY, robotZ
, utmZone);
// updateImagery(
x, y, z
, utmZone);
}
if
(
mActiveUAS
)
...
...
@@ -2003,8 +2044,8 @@ Pixhawk3DWidget::updateTrails(double robotX, double robotY, double robotZ,
}
void
Pixhawk3DWidget
::
updateImagery
(
double
originX
,
double
originY
,
double
originZ
,
const
QString
&
zone
)
Pixhawk3DWidget
::
updateImagery
(
double
originX
,
double
originY
,
const
QString
&
zone
,
MAV_FRAME
frame
)
{
if
(
mImageryNode
->
getImageryType
()
==
Imagery
::
BLANK_MAP
)
{
...
...
@@ -2030,7 +2071,7 @@ Pixhawk3DWidget::updateImagery(double originX, double originY, double originZ,
case
Imagery
:
:
GOOGLE_SATELLITE
:
minResolution
=
0.5
;
break
;
case
Imagery
:
:
SWISSTOPO
_SATELLITE
:
case
Imagery
:
:
OFFLINE
_SATELLITE
:
minResolution
=
0.25
;
maxResolution
=
0.25
;
break
;
...
...
@@ -2049,13 +2090,24 @@ Pixhawk3DWidget::updateImagery(double originX, double originY, double originZ,
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
,
resolution
,
m3DWidget
->
cameraManipulator
()
->
getCenter
().
y
(),
m3DWidget
->
cameraManipulator
()
->
getCenter
().
x
(),
originX
,
originY
,
originZ
,
x
+
xOffset
,
y
+
yOffset
,
-
xOffset
,
-
yOffset
,
zone
);
// prefetch map tiles
...
...
@@ -2063,16 +2115,16 @@ Pixhawk3DWidget::updateImagery(double originX, double originY, double originZ,
{
mImageryNode
->
prefetch3D
(
viewingRadius
/
2.0
,
resolution
/
2.0
,
m3DWidget
->
cameraManipulator
()
->
getCenter
().
y
()
,
m3DWidget
->
cameraManipulator
()
->
getCenter
().
x
()
,
x
+
xOffset
,
y
+
yOffset
,
zone
);
}
if
(
resolution
*
2.0
<=
maxResolution
)
{
mImageryNode
->
prefetch3D
(
viewingRadius
*
2.0
,
resolution
*
2.0
,
m3DWidget
->
cameraManipulator
()
->
getCenter
().
y
()
,
m3DWidget
->
cameraManipulator
()
->
getCenter
().
x
()
,
x
+
xOffset
,
y
+
yOffset
,
zone
);
}
...
...
src/ui/map3D/Pixhawk3DWidget.h
View file @
ee74c2c3
...
...
@@ -60,6 +60,7 @@ public slots:
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
,
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
);
signals:
...
...
@@ -71,6 +72,7 @@ private slots:
void
showTerrainParamWindow
(
void
);
void
showViewParamWindow
(
void
);
void
followCameraChanged
(
int
systemId
);
void
imageryParamsChanged
(
void
);
void
recenterActiveCamera
(
void
);
void
modelChanged
(
int
systemId
,
int
index
);
void
setBirdEyeView
(
void
);
...
...
@@ -143,8 +145,8 @@ private:
void
resizeHUD
(
int
width
,
int
height
);
void
updateHUD
(
UASInterface
*
uas
,
MAV_FRAME
frame
);
void
updateImagery
(
double
originX
,
double
originY
,
double
originZ
,
const
QString
&
zone
);
void
updateImagery
(
double
originX
,
double
originY
,
const
QString
&
zone
,
MAV_FRAME
frame
);
void
updateTarget
(
UASInterface
*
uas
,
MAV_FRAME
frame
,
double
robotX
,
double
robotY
,
double
robotZ
,
QVector4D
&
target
,
...
...
src/ui/map3D/SystemContainer.cc
View file @
ee74c2c3
...
...
@@ -7,6 +7,12 @@ SystemContainer::SystemContainer()
}
QVector3D
&
SystemContainer
::
gpsLocalOrigin
(
void
)
{
return
mGPSLocalOrigin
;
}
QVector4D
&
SystemContainer
::
target
(
void
)
{
...
...
src/ui/map3D/SystemContainer.h
View file @
ee74c2c3
...
...
@@ -4,6 +4,7 @@
#include <osg/Geode>
#include <QMap>
#include <QVarLengthArray>
#include <QVector3D>
#include <QVector4D>
#include "ImageWindowGeode.h"
...
...
@@ -19,6 +20,8 @@ class SystemContainer
public:
SystemContainer
();
QVector3D
&
gpsLocalOrigin
(
void
);
QVector4D
&
target
(
void
);
QVector
<
osg
::
ref_ptr
<
osg
::
Node
>
>&
models
(
void
);
...
...
@@ -43,6 +46,7 @@ public:
#endif
private:
QVector3D
mGPSLocalOrigin
;
QVector4D
mTarget
;
QVector
<
osg
::
ref_ptr
<
osg
::
Node
>
>
mModels
;
...
...
src/ui/map3D/ViewParamWidget.cc
View file @
ee74c2c3
...
...
@@ -6,6 +6,7 @@
#include <QLabel>
#include <QPushButton>
#include "ImageryParamDialog.h"
#include "UASInterface.h"
ViewParamWidget
::
ViewParamWidget
(
GlobalViewParamsPtr
&
globalViewParams
,
...
...
@@ -97,6 +98,12 @@ ViewParamWidget::setpointsCheckBoxToggled(int state)
}
}
void
ViewParamWidget
::
showImageryParamDialog
(
void
)
{
ImageryParamDialog
::
getImageryParams
(
mGlobalViewParams
);
}
void
ViewParamWidget
::
buildLayout
(
QVBoxLayout
*
layout
)
{
...
...
@@ -106,17 +113,15 @@ ViewParamWidget::buildLayout(QVBoxLayout* layout)
frameComboBox
->
addItem
(
"Local"
);
frameComboBox
->
addItem
(
"Global"
);
QComboBox
*
imageryComboBox
=
new
QComboBox
(
this
);
imageryComboBox
->
addItem
(
"None"
);
imageryComboBox
->
addItem
(
"Map (Google)"
);
imageryComboBox
->
addItem
(
"Satellite (Google)"
);
QCheckBox
*
terrainModelCheckBox
=
new
QCheckBox
(
this
);
terrainModelCheckBox
->
setChecked
(
mGlobalViewParams
->
displayTerrain
());
QCheckBox
*
worldGridCheckBox
=
new
QCheckBox
(
this
);
worldGridCheckBox
->
setChecked
(
mGlobalViewParams
->
displayWorldGrid
());
QPushButton
*
imageryButton
=
new
QPushButton
(
this
);
imageryButton
->
setText
(
"View"
);
QMapIterator
<
int
,
SystemViewParamsPtr
>
it
(
mSystemViewParamMap
);
while
(
it
.
hasNext
())
{
...
...
@@ -130,9 +135,9 @@ ViewParamWidget::buildLayout(QVBoxLayout* layout)
QFormLayout
*
formLayout
=
new
QFormLayout
;
formLayout
->
addRow
(
tr
(
"Follow Camera"
),
mFollowCameraComboBox
);
formLayout
->
addRow
(
tr
(
"Frame"
),
frameComboBox
);
formLayout
->
addRow
(
tr
(
"Imagery"
),
imageryComboBox
);
formLayout
->
addRow
(
tr
(
"Terrain"
),
terrainModelCheckBox
);
formLayout
->
addRow
(
tr
(
"World Grid"
),
worldGridCheckBox
);
formLayout
->
addRow
(
tr
(
"Imagery Options"
),
imageryButton
);
layout
->
addLayout
(
formLayout
);
layout
->
addWidget
(
mTabWidget
);
...
...
@@ -142,12 +147,14 @@ ViewParamWidget::buildLayout(QVBoxLayout* layout)
mGlobalViewParams
.
data
(),
SLOT
(
followCameraChanged
(
const
QString
&
)));
connect
(
frameComboBox
,
SIGNAL
(
currentIndexChanged
(
const
QString
&
)),
mGlobalViewParams
.
data
(),
SLOT
(
frameChanged
(
const
QString
&
)));
connect
(
imageryComboBox
,
SIGNAL
(
currentIndexChanged
(
int
)),
mGlobalViewParams
.
data
(),
SLOT
(
imageryTypeChanged
(
int
)));
connect
(
terrainModelCheckBox
,
SIGNAL
(
stateChanged
(
int
)),
mGlobalViewParams
.
data
(),
SLOT
(
toggleTerrain
(
int
)));
connect
(
worldGridCheckBox
,
SIGNAL
(
stateChanged
(
int
)),
mGlobalViewParams
.
data
(),
SLOT
(
toggleWorldGrid
(
int
)));
connect
(
imageryButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
showImageryParamDialog
()));
// connect(imageryComboBox, SIGNAL(currentIndexChanged(int)),
// mGlobalViewParams.data(), SLOT(imageryTypeChanged(int)));
}
void
...
...
src/ui/map3D/ViewParamWidget.h
View file @
ee74c2c3
...
...
@@ -31,6 +31,7 @@ private slots:
void
overlayCreated
(
int
systemId
,
const
QString
&
name
);
void
systemCreated
(
UASInterface
*
uas
);
void
setpointsCheckBoxToggled
(
int
state
);
void
showImageryParamDialog
(
void
);
private:
void
buildLayout
(
QVBoxLayout
*
layout
);
...
...
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