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
08f8dfb8
Commit
08f8dfb8
authored
Feb 24, 2012
by
hengli
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Added additional roll/pitch parameters to terrain offset dialog.
parent
d5c30100
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
63 additions
and
26 deletions
+63
-26
GlobalViewParams.cc
src/ui/map3D/GlobalViewParams.cc
+18
-6
GlobalViewParams.h
src/ui/map3D/GlobalViewParams.h
+8
-4
Pixhawk3DWidget.cc
src/ui/map3D/Pixhawk3DWidget.cc
+8
-6
Q3DWidget.cc
src/ui/map3D/Q3DWidget.cc
+1
-1
TerrainParamDialog.cc
src/ui/map3D/TerrainParamDialog.cc
+26
-9
TerrainParamDialog.h
src/ui/map3D/TerrainParamDialog.h
+2
-0
No files found.
src/ui/map3D/GlobalViewParams.cc
View file @
08f8dfb8
...
...
@@ -72,16 +72,28 @@ GlobalViewParams::frame(void) const
return
mFrame
;
}
QVector
4
D
&
GlobalViewParams
::
terrainOffset
(
void
)
QVector
3
D
&
GlobalViewParams
::
terrain
Position
Offset
(
void
)
{
return
mTerrainOffset
;
return
mTerrain
Position
Offset
;
}
QVector
4
D
GlobalViewParams
::
terrainOffset
(
void
)
const
QVector
3
D
GlobalViewParams
::
terrain
Position
Offset
(
void
)
const
{
return
mTerrainOffset
;
return
mTerrainPositionOffset
;
}
QVector3D
&
GlobalViewParams
::
terrainAttitudeOffset
(
void
)
{
return
mTerrainPositionOffset
;
}
QVector3D
GlobalViewParams
::
terrainAttitudeOffset
(
void
)
const
{
return
mTerrainPositionOffset
;
}
void
...
...
src/ui/map3D/GlobalViewParams.h
View file @
08f8dfb8
...
...
@@ -3,7 +3,7 @@
#include <QObject>
#include <QString>
#include <QVector
4
D>
#include <QVector
3
D>
#include "QGCMAVLink.h"
#include "Imagery.h"
...
...
@@ -30,8 +30,11 @@ public:
MAV_FRAME
&
frame
(
void
);
MAV_FRAME
frame
(
void
)
const
;
QVector4D
&
terrainOffset
(
void
);
QVector4D
terrainOffset
(
void
)
const
;
QVector3D
&
terrainPositionOffset
(
void
);
QVector3D
terrainPositionOffset
(
void
)
const
;
QVector3D
&
terrainAttitudeOffset
(
void
);
QVector3D
terrainAttitudeOffset
(
void
)
const
;
public
slots
:
void
followCameraChanged
(
const
QString
&
text
);
...
...
@@ -49,7 +52,8 @@ private:
Imagery
::
Type
mImageryType
;
int
mFollowCameraId
;
MAV_FRAME
mFrame
;
QVector4D
mTerrainOffset
;
QVector3D
mTerrainPositionOffset
;
QVector3D
mTerrainAttitudeOffset
;
};
typedef
QSharedPointer
<
GlobalViewParams
>
GlobalViewParamsPtr
;
...
...
src/ui/map3D/Pixhawk3DWidget.cc
View file @
08f8dfb8
...
...
@@ -416,12 +416,13 @@ Pixhawk3DWidget::showTerrainParamWindow(void)
{
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
->
setAttitude
(
osg
::
Quat
(
M_PI_2
-
terrainOffset
.
w
(),
osg
::
Vec3d
(
0.0
f
,
0.0
f
,
1.0
f
),
0.0
,
osg
::
Vec3d
(
1.0
f
,
0.0
f
,
0.0
f
),
0.0
,
osg
::
Vec3d
(
0.0
f
,
1.0
f
,
0.0
f
)));
mTerrainPAT
->
setPosition
(
osg
::
Vec3d
(
positionOffset
.
y
(),
positionOffset
.
x
(),
-
positio
nOffset
.
z
()));
mTerrainPAT
->
setAttitude
(
osg
::
Quat
(
M_PI_2
-
attitudeOffset
.
z
(),
osg
::
Vec3d
(
0.0
f
,
0.0
f
,
1.0
f
),
attitudeOffset
.
y
()
,
osg
::
Vec3d
(
1.0
f
,
0.0
f
,
0.0
f
),
attitudeOffset
.
x
()
,
osg
::
Vec3d
(
0.0
f
,
1.0
f
,
0.0
f
)));
}
void
...
...
@@ -534,7 +535,8 @@ Pixhawk3DWidget::loadTerrainModel(void)
mTerrainNode
->
setName
(
"terrain"
);
mTerrainPAT
->
addChild
(
mTerrainNode
);
mGlobalViewParams
->
terrainOffset
()
=
QVector4D
();
mGlobalViewParams
->
terrainPositionOffset
()
=
QVector3D
();
mGlobalViewParams
->
terrainAttitudeOffset
()
=
QVector3D
();
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
),
...
...
src/ui/map3D/Q3DWidget.cc
View file @
08f8dfb8
...
...
@@ -61,7 +61,7 @@ Q3DWidget::Q3DWidget(QWidget* parent)
mOsgGW
=
new
osgViewer
::
GraphicsWindowEmbedded
(
0
,
0
,
width
(),
height
());
setThreadingModel
(
osgViewer
::
Viewer
::
SingleThreaded
);
setThreadingModel
(
osgViewer
::
Viewer
::
CullDrawThreadPerContext
);
setMouseTracking
(
true
);
}
...
...
src/ui/map3D/TerrainParamDialog.cc
View file @
08f8dfb8
...
...
@@ -19,20 +19,25 @@ TerrainParamDialog::TerrainParamDialog(QWidget* parent)
void
TerrainParamDialog
::
getTerrainParams
(
GlobalViewParamsPtr
&
globalViewParams
)
{
QVector4D
&
terrainOffset
=
globalViewParams
->
terrainOffset
();
QVector3D
&
positionOffset
=
globalViewParams
->
terrainPositionOffset
();
QVector3D
&
attitudeOffset
=
globalViewParams
->
terrainAttitudeOffset
();
TerrainParamDialog
dialog
;
dialog
.
mXOffsetSpinBox
->
setValue
(
terrainOffset
.
x
());
dialog
.
mYOffsetSpinBox
->
setValue
(
terrainOffset
.
y
());
dialog
.
mZOffsetSpinBox
->
setValue
(
terrainOffset
.
z
());
dialog
.
mYawOffsetSpinBox
->
setValue
(
osg
::
RadiansToDegrees
(
terrainOffset
.
w
()));
dialog
.
mXOffsetSpinBox
->
setValue
(
positionOffset
.
x
());
dialog
.
mYOffsetSpinBox
->
setValue
(
positionOffset
.
y
());
dialog
.
mZOffsetSpinBox
->
setValue
(
positionOffset
.
z
());
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
)
{
terrainOffset
.
setX
(
dialog
.
mXOffsetSpinBox
->
value
());
terrainOffset
.
setY
(
dialog
.
mYOffsetSpinBox
->
value
());
terrainOffset
.
setZ
(
dialog
.
mZOffsetSpinBox
->
value
());
terrainOffset
.
setW
(
osg
::
DegreesToRadians
(
dialog
.
mYawOffsetSpinBox
->
value
()));
positionOffset
.
setX
(
dialog
.
mXOffsetSpinBox
->
value
());
positionOffset
.
setY
(
dialog
.
mYOffsetSpinBox
->
value
());
positionOffset
.
setZ
(
dialog
.
mZOffsetSpinBox
->
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)
mZOffsetSpinBox
->
setRange
(
-
100.0
,
100.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
->
setDecimals
(
0
);
mYawOffsetSpinBox
->
setRange
(
-
180.0
,
180.0
);
...
...
@@ -77,6 +92,8 @@ TerrainParamDialog::buildLayout(QVBoxLayout* layout)
formLayout
->
addRow
(
tr
(
"x (m)"
),
mXOffsetSpinBox
);
formLayout
->
addRow
(
tr
(
"y (m)"
),
mYOffsetSpinBox
);
formLayout
->
addRow
(
tr
(
"z (m)"
),
mZOffsetSpinBox
);
formLayout
->
addRow
(
tr
(
"Roll (deg)"
),
mRollOffsetSpinBox
);
formLayout
->
addRow
(
tr
(
"Pitch (deg)"
),
mPitchOffsetSpinBox
);
formLayout
->
addRow
(
tr
(
"Yaw (deg)"
),
mYawOffsetSpinBox
);
offsetGroupBox
->
setLayout
(
formLayout
);
...
...
src/ui/map3D/TerrainParamDialog.h
View file @
08f8dfb8
...
...
@@ -26,6 +26,8 @@ private:
QDoubleSpinBox
*
mXOffsetSpinBox
;
QDoubleSpinBox
*
mYOffsetSpinBox
;
QDoubleSpinBox
*
mZOffsetSpinBox
;
QDoubleSpinBox
*
mRollOffsetSpinBox
;
QDoubleSpinBox
*
mPitchOffsetSpinBox
;
QDoubleSpinBox
*
mYawOffsetSpinBox
;
};
...
...
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