diff --git a/src/ui/map3D/GlobalViewParams.cc b/src/ui/map3D/GlobalViewParams.cc index 853bbfebfc9161f1d1109fd77232eac9bf5e2f3a..42cb1a524f0b0d54c159ebc9451370ad488b177d 100644 --- a/src/ui/map3D/GlobalViewParams.cc +++ b/src/ui/map3D/GlobalViewParams.cc @@ -72,16 +72,28 @@ GlobalViewParams::frame(void) const return mFrame; } -QVector4D& -GlobalViewParams::terrainOffset(void) +QVector3D& +GlobalViewParams::terrainPositionOffset(void) { - return mTerrainOffset; + return mTerrainPositionOffset; } -QVector4D -GlobalViewParams::terrainOffset(void) const +QVector3D +GlobalViewParams::terrainPositionOffset(void) const { - return mTerrainOffset; + return mTerrainPositionOffset; +} + +QVector3D& +GlobalViewParams::terrainAttitudeOffset(void) +{ + return mTerrainPositionOffset; +} + +QVector3D +GlobalViewParams::terrainAttitudeOffset(void) const +{ + return mTerrainPositionOffset; } void diff --git a/src/ui/map3D/GlobalViewParams.h b/src/ui/map3D/GlobalViewParams.h index a6a8728e80999b1fe739e8838593ef83fd7290f3..0a62e97c66e5de67309f017eca1ca6e46de83067 100644 --- a/src/ui/map3D/GlobalViewParams.h +++ b/src/ui/map3D/GlobalViewParams.h @@ -3,7 +3,7 @@ #include #include -#include +#include #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 GlobalViewParamsPtr; diff --git a/src/ui/map3D/Pixhawk3DWidget.cc b/src/ui/map3D/Pixhawk3DWidget.cc index f6be32e30f76016d7d4c89119663218e2cfabde5..ccc1d6bb07e823ea78278a02aa78b152ea8d0930 100644 --- a/src/ui/map3D/Pixhawk3DWidget.cc +++ b/src/ui/map3D/Pixhawk3DWidget.cc @@ -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(), -terrainOffset.z())); - mTerrainPAT->setAttitude(osg::Quat(M_PI_2 - terrainOffset.w(), osg::Vec3d(0.0f, 0.0f, 1.0f), - 0.0, osg::Vec3d(1.0f, 0.0f, 0.0f), - 0.0, osg::Vec3d(0.0f, 1.0f, 0.0f))); + mTerrainPAT->setPosition(osg::Vec3d(positionOffset.y(), positionOffset.x(), -positionOffset.z())); + mTerrainPAT->setAttitude(osg::Quat(M_PI_2 - attitudeOffset.z(), osg::Vec3d(0.0f, 0.0f, 1.0f), + attitudeOffset.y(), osg::Vec3d(1.0f, 0.0f, 0.0f), + attitudeOffset.x(), osg::Vec3d(0.0f, 1.0f, 0.0f))); } 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.0f, 0.0f, 1.0f), diff --git a/src/ui/map3D/Q3DWidget.cc b/src/ui/map3D/Q3DWidget.cc index d05fdcc606e768077b9b3b01afb06338377e94a0..1ec2721d456d6a6fd3d366e5ce6fb5c296937a44 100644 --- a/src/ui/map3D/Q3DWidget.cc +++ b/src/ui/map3D/Q3DWidget.cc @@ -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); } diff --git a/src/ui/map3D/TerrainParamDialog.cc b/src/ui/map3D/TerrainParamDialog.cc index e2daf5d9f228016b2d840987a2806b1843f8bdde..1fd78267b2cddb286a8a75b1fc4d30e29826d6ee 100644 --- a/src/ui/map3D/TerrainParamDialog.cc +++ b/src/ui/map3D/TerrainParamDialog.cc @@ -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); diff --git a/src/ui/map3D/TerrainParamDialog.h b/src/ui/map3D/TerrainParamDialog.h index ffa5a1c4f8740b3e13fe340bd564f4564aa64a5f..2a0f0f20044bf100e988d271bcc45333bbe94c08 100644 --- a/src/ui/map3D/TerrainParamDialog.h +++ b/src/ui/map3D/TerrainParamDialog.h @@ -26,6 +26,8 @@ private: QDoubleSpinBox* mXOffsetSpinBox; QDoubleSpinBox* mYOffsetSpinBox; QDoubleSpinBox* mZOffsetSpinBox; + QDoubleSpinBox* mRollOffsetSpinBox; + QDoubleSpinBox* mPitchOffsetSpinBox; QDoubleSpinBox* mYawOffsetSpinBox; };