Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
08f8dfb8
Commit
08f8dfb8
authored
Feb 24, 2012
by
hengli
Browse files
Added additional roll/pitch parameters to terrain offset dialog.
parent
d5c30100
Changes
6
Hide whitespace changes
Inline
Side-by-side
src/ui/map3D/GlobalViewParams.cc
View file @
08f8dfb8
...
@@ -72,16 +72,28 @@ GlobalViewParams::frame(void) const
...
@@ -72,16 +72,28 @@ GlobalViewParams::frame(void) const
return
mFrame
;
return
mFrame
;
}
}
QVector
4
D
&
QVector
3
D
&
GlobalViewParams
::
terrainOffset
(
void
)
GlobalViewParams
::
terrain
Position
Offset
(
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
mTerrainPositionOffset
;
}
QVector3D
GlobalViewParams
::
terrainAttitudeOffset
(
void
)
const
{
return
mTerrainPositionOffset
;
}
}
void
void
...
...
src/ui/map3D/GlobalViewParams.h
View file @
08f8dfb8
...
@@ -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"
...
@@ -30,8 +30,11 @@ public:
...
@@ -30,8 +30,11 @@ public:
MAV_FRAME
&
frame
(
void
);
MAV_FRAME
&
frame
(
void
);
MAV_FRAME
frame
(
void
)
const
;
MAV_FRAME
frame
(
void
)
const
;
QVector4D
&
terrainOffset
(
void
);
QVector3D
&
terrainPositionOffset
(
void
);
QVector4D
terrainOffset
(
void
)
const
;
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
);
...
@@ -49,7 +52,8 @@ private:
...
@@ -49,7 +52,8 @@ private:
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/Pixhawk3DWidget.cc
View file @
08f8dfb8
...
@@ -416,12 +416,13 @@ Pixhawk3DWidget::showTerrainParamWindow(void)
...
@@ -416,12 +416,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
(
terrai
nOffset
.
y
(),
terrai
nOffset
.
x
(),
-
terrai
nOffset
.
z
()));
mTerrainPAT
->
setPosition
(
osg
::
Vec3d
(
positio
nOffset
.
y
(),
positio
nOffset
.
x
(),
-
positio
nOffset
.
z
()));
mTerrainPAT
->
setAttitude
(
osg
::
Quat
(
M_PI_2
-
terrain
Offset
.
w
(),
osg
::
Vec3d
(
0.0
f
,
0.0
f
,
1.0
f
),
mTerrainPAT
->
setAttitude
(
osg
::
Quat
(
M_PI_2
-
attitude
Offset
.
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
...
@@ -534,7 +535,8 @@ Pixhawk3DWidget::loadTerrainModel(void)
...
@@ -534,7 +535,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
),
...
...
src/ui/map3D/Q3DWidget.cc
View file @
08f8dfb8
...
@@ -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/TerrainParamDialog.cc
View file @
08f8dfb8
...
@@ -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 @
08f8dfb8
...
@@ -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
;
};
};
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new 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