diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 3a6bf1c9af8241e611bac3c0b2ffa61fc64e1c8b..5491c61fc0047f9494010a5f7b7f96cb9002548b 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -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") @@ -602,4 +604,4 @@ win32-msvc2008|win32-msvc2010|linux { # TO DO: build library when it does not exist already LIBS += -LthirdParty/libxbee/lib \ -llibxbee -} \ No newline at end of file +} diff --git a/src/ui/map3D/GLOverlayGeode.cc b/src/ui/map3D/GLOverlayGeode.cc index fdf183788007c02e29539944dcd583b9e10eb111..86cb6f8ed137c959a692a3e5ae362174c6792fc8 100644 --- a/src/ui/map3D/GLOverlayGeode.cc +++ b/src/ui/map3D/GLOverlayGeode.cc @@ -36,14 +36,16 @@ GLOverlayGeode::messageTimestamp(void) const GLOverlayGeode::GLOverlayDrawable::GLOverlayDrawable() { - setUseDisplayList(true); + setUseDisplayList(false); + setUseVertexBufferObjects(true); } GLOverlayGeode::GLOverlayDrawable::GLOverlayDrawable(const GLOverlayDrawable& drawable, const osg::CopyOp& copyop) : osg::Drawable(drawable,copyop) { - setUseDisplayList(true); + setUseDisplayList(false); + setUseVertexBufferObjects(true); } void @@ -136,8 +138,6 @@ GLOverlayGeode::GLOverlayDrawable::setOverlay(px::GLOverlay &overlay) break; } } - - dirtyDisplayList(); } void @@ -148,9 +148,11 @@ GLOverlayGeode::GLOverlayDrawable::drawImplementation(osg::RenderInfo&) const return; } + glMatrixMode(GL_MODELVIEW); + glDisable(GL_LIGHTING); glPushMatrix(); - glScalef(-1.0f, 1.0f, 1.0f); + glScalef(-1.0f, 1.0f, -1.0f); glRotatef(90.0f, 0.0f, 0.0f, 1.0f); const std::string& data = mOverlay.data(); @@ -401,6 +403,7 @@ GLOverlayGeode::GLOverlayDrawable::drawImplementation(osg::RenderInfo&) const } glPopMatrix(); + glEnable(GL_LIGHTING); } osg::BoundingBox diff --git a/src/ui/map3D/GlobalViewParams.cc b/src/ui/map3D/GlobalViewParams.cc index 853bbfebfc9161f1d1109fd77232eac9bf5e2f3a..12b1ea5130eafe1efc6d9e1307e0657a97c652e3 100644 --- a/src/ui/map3D/GlobalViewParams.cc +++ b/src/ui/map3D/GlobalViewParams.cc @@ -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,16 +96,34 @@ GlobalViewParams::frame(void) const return mFrame; } -QVector4D& -GlobalViewParams::terrainOffset(void) +void +GlobalViewParams::signalImageryParamsChanged(void) +{ + emit imageryParamsChanged(); +} + +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 mTerrainAttitudeOffset; +} + +QVector3D +GlobalViewParams::terrainAttitudeOffset(void) const +{ + return mTerrainAttitudeOffset; } void @@ -120,12 +162,6 @@ GlobalViewParams::frameChanged(const QString& text) } } -void -GlobalViewParams::imageryTypeChanged(int index) -{ - mImageryType = static_cast(index); -} - void GlobalViewParams::toggleWorldGrid(int state) { diff --git a/src/ui/map3D/GlobalViewParams.h b/src/ui/map3D/GlobalViewParams.h index a6a8728e80999b1fe739e8838593ef83fd7290f3..62b8651cd40062d4ec7d61c9ee12337062602e43 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" @@ -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,26 +36,34 @@ public: MAV_FRAME& frame(void); MAV_FRAME frame(void) const; - QVector4D& terrainOffset(void); - QVector4D terrainOffset(void) const; + void signalImageryParamsChanged(void); + + QVector3D& terrainPositionOffset(void); + QVector3D terrainPositionOffset(void) const; + + QVector3D& terrainAttitudeOffset(void); + QVector3D terrainAttitudeOffset(void) const; 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; - QVector4D mTerrainOffset; + QVector3D mTerrainPositionOffset; + QVector3D mTerrainAttitudeOffset; }; typedef QSharedPointer GlobalViewParamsPtr; diff --git a/src/ui/map3D/Imagery.cc b/src/ui/map3D/Imagery.cc index 2d1c50a261bd927573471e42e1efbcf8f7617311..d5c39740dea255305a3204af82c07190ce238548 100644 --- a/src/ui/map3D/Imagery.cc +++ b/src/ui/map3D/Imagery.cc @@ -32,6 +32,7 @@ This file is part of the QGROUNDCONTROL project #include "Imagery.h" #include +#include #include #include @@ -41,28 +42,39 @@ const double WGS84_ECCSQ = 0.00669437999013; const int MAX_ZOOM_LEVEL = 20; 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::getImageryType(void) const { - return currentImageryType; + return mImageryType; } void 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 -Imagery::setOffset(double xOffset, double yOffset) +Imagery::setPath(const QString &path) { - this->xOffset = xOffset; - this->yOffset = yOffset; + 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 = textureCache->get(url); + TexturePtr t = mTextureCache->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 = textureCache->get(url); + TexturePtr t = mTextureCache->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 = textureCache->get(tileURL); + TexturePtr t = mTextureCache->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) { - textureCache->sync(); + mTextureCache->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(rint(log2(tileResolution))); int numTiles = static_cast(exp2(static_cast(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(rint(minUtmX / utmMultiplier)); @@ -312,11 +355,13 @@ Imagery::tileBounds(double tileResolution, maxTileY = static_cast(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(rint(tileResolution)); } oss << "-" << tileY << "-" << tileX << ".jpg"; diff --git a/src/ui/map3D/Imagery.h b/src/ui/map3D/Imagery.h index 15f1b00a3ad572979a52aa3cb0bae1a245b683d3..ab938356db90825a8156e8cdad83414b0d0314b8 100644 --- a/src/ui/map3D/Imagery.h +++ b/src/ui/map3D/Imagery.h @@ -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; + QScopedPointer mTextureCache; - Type currentImageryType; + Type mImageryType; + std::string mImageryPath; - double xOffset; - double yOffset; + double mXOffset; + double mYOffset; + double mZOffset; }; #endif // IMAGERY_H diff --git a/src/ui/map3D/ImageryParamDialog.cc b/src/ui/map3D/ImageryParamDialog.cc new file mode 100644 index 0000000000000000000000000000000000000000..6c0a6f4d5e0c3208e28ef9513315d023166207c9 --- /dev/null +++ b/src/ui/map3D/ImageryParamDialog.cc @@ -0,0 +1,174 @@ +#include "ImageryParamDialog.h" + +#include +#include +#include +#include +#include + +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())); +} diff --git a/src/ui/map3D/ImageryParamDialog.h b/src/ui/map3D/ImageryParamDialog.h new file mode 100644 index 0000000000000000000000000000000000000000..0dcbfeb8a967c3d554cc259ae2fe8250ff47915d --- /dev/null +++ b/src/ui/map3D/ImageryParamDialog.h @@ -0,0 +1,36 @@ +#ifndef IMAGERYPARAMDIALOG_H +#define IMAGERYPARAMDIALOG_H + +#include +#include +#include +#include +#include + +#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 diff --git a/src/ui/map3D/Pixhawk3DWidget.cc b/src/ui/map3D/Pixhawk3DWidget.cc index 4bbdf36af3bece6eb2d9863f4a3ec5db71fb8696..da1351cd717b123bc6e19f6240d5f066730679da 100644 --- a/src/ui/map3D/Pixhawk3DWidget.cc +++ b/src/ui/map3D/Pixhawk3DWidget.cc @@ -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(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); @@ -341,6 +346,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) @@ -424,12 +443,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 @@ -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 Pixhawk3DWidget::recenterActiveCamera(void) { @@ -542,7 +572,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), @@ -987,8 +1018,6 @@ Pixhawk3DWidget::update(void) #endif } - mImageryNode->setImageryType(mGlobalViewParams->imageryType()); - if (mFollowCameraId != -1) { UASInterface* uas = UASManager::instance()->getUASForId(mFollowCameraId); @@ -1097,13 +1126,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) @@ -2009,8 +2052,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) { @@ -2018,9 +2061,9 @@ Pixhawk3DWidget::updateImagery(double originX, double originY, double originZ, } double viewingRadius = m3DWidget->cameraManipulator()->getDistance() * 10.0; - if (viewingRadius < 100.0) + if (viewingRadius < 200.0) { - viewingRadius = 100.0; + viewingRadius = 200.0; } double minResolution = 0.25; @@ -2036,7 +2079,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; @@ -2055,13 +2098,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 @@ -2069,16 +2123,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); } diff --git a/src/ui/map3D/Pixhawk3DWidget.h b/src/ui/map3D/Pixhawk3DWidget.h index 4a521997d8512fab4db1c36c7089fc0bded23072..ce2fc6fe77a085979d88cd0e02d86e94056f4197 100644 --- a/src/ui/map3D/Pixhawk3DWidget.h +++ b/src/ui/map3D/Pixhawk3DWidget.h @@ -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, 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/SystemContainer.cc b/src/ui/map3D/SystemContainer.cc index 72cac8eee21eb6c9496c2b1e8525f04ef5cd454e..f74d81e0759c669069b9680e6c5b32e7418867a4 100644 --- a/src/ui/map3D/SystemContainer.cc +++ b/src/ui/map3D/SystemContainer.cc @@ -7,6 +7,12 @@ SystemContainer::SystemContainer() } +QVector3D& +SystemContainer::gpsLocalOrigin(void) +{ + return mGPSLocalOrigin; +} + QVector4D& SystemContainer::target(void) { diff --git a/src/ui/map3D/SystemContainer.h b/src/ui/map3D/SystemContainer.h index 92d7ea68bf8a213a46dc450c109748cf4dea5094..dfee5391bbe38e7c236aca67924942c3ed3ed57b 100644 --- a/src/ui/map3D/SystemContainer.h +++ b/src/ui/map3D/SystemContainer.h @@ -4,6 +4,7 @@ #include #include #include +#include #include #include "ImageWindowGeode.h" @@ -19,6 +20,8 @@ class SystemContainer public: SystemContainer(); + QVector3D& gpsLocalOrigin(void); + QVector4D& target(void); QVector< osg::ref_ptr >& models(void); @@ -43,6 +46,7 @@ public: #endif private: + QVector3D mGPSLocalOrigin; QVector4D mTarget; QVector< osg::ref_ptr > mModels; 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; }; diff --git a/src/ui/map3D/Texture.cc b/src/ui/map3D/Texture.cc index 77691888a1ef7be3cc7006ea4e50edb7df6df87c..e7dc3c741b5ea7fe967a303a63897ac42a803f50 100644 --- a/src/ui/map3D/Texture.cc +++ b/src/ui/map3D/Texture.cc @@ -25,7 +25,7 @@ This file is part of the QGROUNDCONTROL project * @file * @brief Definition of the class Texture. * - * @author Lionel Heng + * @author Lionel Heng * */ @@ -33,77 +33,86 @@ This file is part of the QGROUNDCONTROL project #include "Texture.h" -Texture::Texture(unsigned int _id) - : id(_id) - , texture2D(new osg::Texture2D) - , geometry(new osg::Geometry) +Texture::Texture(quint64 id) + : mId(id) + , mTexture2D(new osg::Texture2D) + , mGeometry(new osg::Geometry) { - texture2D->setFilter(osg::Texture::MIN_FILTER, osg::Texture::NEAREST); - texture2D->setFilter(osg::Texture::MAG_FILTER, osg::Texture::NEAREST); + mTexture2D->setFilter(osg::Texture::MIN_FILTER, osg::Texture::NEAREST); + mTexture2D->setFilter(osg::Texture::MAG_FILTER, osg::Texture::NEAREST); - texture2D->setDataVariance(osg::Object::DYNAMIC); - texture2D->setResizeNonPowerOfTwoHint(false); + mTexture2D->setDataVariance(osg::Object::DYNAMIC); + mTexture2D->setResizeNonPowerOfTwoHint(false); osg::ref_ptr image = new osg::Image; - texture2D->setImage(image); + mTexture2D->setImage(image); osg::ref_ptr vertices(new osg::Vec3dArray(4)); - geometry->setVertexArray(vertices); + mGeometry->setVertexArray(vertices); osg::ref_ptr textureCoords = new osg::Vec2Array; textureCoords->push_back(osg::Vec2(0.0f, 1.0f)); textureCoords->push_back(osg::Vec2(1.0f, 1.0f)); textureCoords->push_back(osg::Vec2(1.0f, 0.0f)); textureCoords->push_back(osg::Vec2(0.0f, 0.0f)); - geometry->setTexCoordArray(0, textureCoords); + mGeometry->setTexCoordArray(0, textureCoords); - geometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::LINES, + mGeometry->addPrimitiveSet(new osg::DrawArrays(osg::PrimitiveSet::LINES, 0, 4)); osg::ref_ptr colors(new osg::Vec4Array); colors->push_back(osg::Vec4(0.0f, 0.0f, 1.0f, 1.0f)); - geometry->setColorArray(colors); - geometry->setColorBinding(osg::Geometry::BIND_OVERALL); + mGeometry->setColorArray(colors); + mGeometry->setColorBinding(osg::Geometry::BIND_OVERALL); - geometry->setUseDisplayList(false); + mGeometry->setUseDisplayList(false); osg::ref_ptr linewidth(new osg::LineWidth); linewidth->setWidth(2.0f); - geometry->getOrCreateStateSet()-> + mGeometry->getOrCreateStateSet()-> setAttributeAndModes(linewidth, osg::StateAttribute::ON); - geometry->getOrCreateStateSet()-> + mGeometry->getOrCreateStateSet()-> setMode(GL_LIGHTING, osg::StateAttribute::OFF); } const QString& Texture::getSourceURL(void) const { - return sourceURL; + return mSourceURL; +} + +void +Texture::setId(quint64 id) +{ + mId = id; } void Texture::sync(const WebImagePtr& image) { - state = static_cast(image->getState()); + mState = static_cast(image->getState()); if (image->getState() != WebImage::UNINITIALIZED && - sourceURL != image->getSourceURL()) { - sourceURL = image->getSourceURL(); + mSourceURL != image->getSourceURL()) + { + mSourceURL = image->getSourceURL(); } - if (image->getState() == WebImage::READY && image->getSyncFlag()) { + if (image->getState() == WebImage::READY && image->getSyncFlag()) + { image->setSyncFlag(false); - if (texture2D->getImage() != NULL) { - texture2D->getImage()->setImage(image->getWidth(), - image->getHeight(), - 1, - GL_RGBA, - GL_RGBA, - GL_UNSIGNED_BYTE, - image->getImageData(), - osg::Image::NO_DELETE); - texture2D->getImage()->dirty(); + if (mTexture2D->getImage() != NULL) + { + mTexture2D->getImage()->setImage(image->getWidth(), + image->getHeight(), + 1, + GL_RGBA, + GL_RGBA, + GL_UNSIGNED_BYTE, + image->getImageData(), + osg::Image::NO_DELETE); + mTexture2D->getImage()->dirty(); } } } @@ -123,40 +132,44 @@ Texture::draw(double x1, double y1, double x2, double y2, bool smoothInterpolation) const { osg::Vec3dArray* vertices = - static_cast(geometry->getVertexArray()); + static_cast(mGeometry->getVertexArray()); (*vertices)[0].set(x1, y1, z); (*vertices)[1].set(x2, y2, z); (*vertices)[2].set(x3, y3, z); (*vertices)[3].set(x4, y4, z); osg::DrawArrays* drawarrays = - static_cast(geometry->getPrimitiveSet(0)); + static_cast(mGeometry->getPrimitiveSet(0)); osg::Vec4Array* colors = - static_cast(geometry->getColorArray()); + static_cast(mGeometry->getColorArray()); - if (state == REQUESTED) { + if (mState == REQUESTED) + { drawarrays->set(osg::PrimitiveSet::LINE_LOOP, 0, 4); (*colors)[0].set(0.0f, 0.0f, 1.0f, 1.0f); - geometry->getOrCreateStateSet()-> - setTextureAttributeAndModes(0, texture2D, osg::StateAttribute::OFF); + mGeometry->getOrCreateStateSet()-> + setTextureAttributeAndModes(0, mTexture2D, osg::StateAttribute::OFF); - return geometry; + return mGeometry; } - if (smoothInterpolation) { - texture2D->setFilter(osg::Texture::MIN_FILTER, osg::Texture::LINEAR); - texture2D->setFilter(osg::Texture::MAG_FILTER, osg::Texture::LINEAR); - } else { - texture2D->setFilter(osg::Texture::MIN_FILTER, osg::Texture::NEAREST); - texture2D->setFilter(osg::Texture::MAG_FILTER, osg::Texture::NEAREST); + if (smoothInterpolation) + { + mTexture2D->setFilter(osg::Texture::MIN_FILTER, osg::Texture::LINEAR); + mTexture2D->setFilter(osg::Texture::MAG_FILTER, osg::Texture::LINEAR); + } + 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); (*colors)[0].set(1.0f, 1.0f, 1.0f, 1.0f); - geometry->getOrCreateStateSet()-> - setTextureAttributeAndModes(0, texture2D, osg::StateAttribute::ON); + mGeometry->getOrCreateStateSet()-> + setTextureAttributeAndModes(0, mTexture2D, osg::StateAttribute::ON); - return geometry; + return mGeometry; } diff --git a/src/ui/map3D/Texture.h b/src/ui/map3D/Texture.h index b953849674d39cde17d50d64820915d50186d477..b1250aa5a6267675064739eac235dd4205c29a2b 100644 --- a/src/ui/map3D/Texture.h +++ b/src/ui/map3D/Texture.h @@ -25,7 +25,7 @@ This file is part of the QGROUNDCONTROL project * @file * @brief Definition of the class Texture. * - * @author Lionel Heng + * @author Lionel Heng * */ @@ -43,11 +43,11 @@ This file is part of the QGROUNDCONTROL project class Texture { public: - explicit Texture(unsigned int _id); + explicit Texture(quint64 id); const QString& getSourceURL(void) const; - void setId(unsigned int _id); + void setId(quint64 id); void sync(const WebImagePtr& image); @@ -60,17 +60,18 @@ public: bool smoothInterpolation) const; private: - enum State { + enum State + { UNINITIALIZED = 0, REQUESTED = 1, READY = 2 }; - State state; - QString sourceURL; - unsigned int id; - osg::ref_ptr texture2D; - osg::ref_ptr geometry; + State mState; + QString mSourceURL; + quint64 mId; + osg::ref_ptr mTexture2D; + osg::ref_ptr mGeometry; }; typedef QSharedPointer TexturePtr; diff --git a/src/ui/map3D/TextureCache.cc b/src/ui/map3D/TextureCache.cc index 8681c6811cb5d7787d429f49598f5b8af871500d..6b9ebc9e9e3a5ccaa6eb7117397b51d106900e89 100644 --- a/src/ui/map3D/TextureCache.cc +++ b/src/ui/map3D/TextureCache.cc @@ -25,34 +25,37 @@ This file is part of the QGROUNDCONTROL project * @file * @brief Definition of the class TextureCache. * - * @author Lionel Heng + * @author Lionel Heng * */ #include "TextureCache.h" -TextureCache::TextureCache(uint32_t _cacheSize) - : cacheSize(_cacheSize) - , imageCache(new WebImageCache(0, cacheSize)) +TextureCache::TextureCache(int cacheSize) + : mCacheSize(cacheSize) + , mImageCache(new WebImageCache(0, cacheSize)) { - for (uint32_t i = 0; i < cacheSize; ++i) { + for (int i = 0; i < mCacheSize; ++i) + { TexturePtr t(new Texture(i)); - textures.push_back(t); + mTextures.push_back(t); } } TexturePtr TextureCache::get(const QString& tileURL) { - QPair p1 = lookup(tileURL); - if (!p1.first.isNull()) { + QPair p1 = lookup(tileURL); + if (!p1.first.isNull()) + { return p1.first; } - QPair p2 = imageCache->lookup(tileURL); - if (!p2.first.isNull()) { - textures[p2.second]->sync(p2.first); + QPair p2 = mImageCache->lookup(tileURL); + if (!p2.first.isNull()) + { + mTextures[p2.second]->sync(p2.first); p1 = lookup(tileURL); return p1.first; @@ -64,19 +67,23 @@ TextureCache::get(const QString& tileURL) void TextureCache::sync(void) { - if (requireSync()) { - for (int32_t i = 0; i < textures.size(); ++i) { - textures[i]->sync(imageCache->at(i)); + if (requireSync()) + { + for (int i = 0; i < mTextures.size(); ++i) + { + mTextures[i]->sync(mImageCache->at(i)); } } } -QPair +QPair TextureCache::lookup(const QString& tileURL) { - for (int32_t i = 0; i < textures.size(); ++i) { - if (textures[i]->getSourceURL() == tileURL) { - return qMakePair(textures[i], i); + for (int i = 0; i < mTextures.size(); ++i) + { + if (mTextures[i]->getSourceURL() == tileURL) + { + return qMakePair(mTextures[i], i); } } @@ -86,8 +93,10 @@ TextureCache::lookup(const QString& tileURL) bool TextureCache::requireSync(void) const { - for (uint32_t i = 0; i < cacheSize; ++i) { - if (imageCache->at(i)->getSyncFlag()) { + for (int i = 0; i < mCacheSize; ++i) + { + if (mImageCache->at(i)->getSyncFlag()) + { return true; } } diff --git a/src/ui/map3D/TextureCache.h b/src/ui/map3D/TextureCache.h index 25be665b90f82560549d35237e17688566432a53..14597b23415085707d5a511788639a12a27473f1 100644 --- a/src/ui/map3D/TextureCache.h +++ b/src/ui/map3D/TextureCache.h @@ -25,7 +25,7 @@ This file is part of the QGROUNDCONTROL project * @file * @brief Definition of the class TextureCache. * - * @author Lionel Heng + * @author Lionel Heng * */ @@ -40,7 +40,7 @@ This file is part of the QGROUNDCONTROL project class TextureCache { public: - explicit TextureCache(uint32_t cacheSize); + explicit TextureCache(int cacheSize); TexturePtr get(const QString& tileURL); @@ -51,10 +51,10 @@ private: bool requireSync(void) const; - uint32_t cacheSize; - QVector textures; + int mCacheSize; + QVector mTextures; - QScopedPointer imageCache; + QScopedPointer mImageCache; }; #endif // TEXTURECACHE_H diff --git a/src/ui/map3D/ViewParamWidget.cc b/src/ui/map3D/ViewParamWidget.cc index 067b3f2a53da8128cb9954c3241d6adec302d9c2..e28ff9ed43073c46e16e942197d88135a1e5f0fb 100644 --- a/src/ui/map3D/ViewParamWidget.cc +++ b/src/ui/map3D/ViewParamWidget.cc @@ -6,6 +6,7 @@ #include #include +#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 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 diff --git a/src/ui/map3D/ViewParamWidget.h b/src/ui/map3D/ViewParamWidget.h index 69142f090441dedf1594814e2eedc47af3ec6264..d10af19d20c2bd58a750b0785cc0eafae9f4d1a9 100644 --- a/src/ui/map3D/ViewParamWidget.h +++ b/src/ui/map3D/ViewParamWidget.h @@ -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); diff --git a/src/ui/map3D/WebImage.cc b/src/ui/map3D/WebImage.cc index d09f96dd0c335e09255a2441687fba45f2e45a11..c638b811fa9b32f71a7e1b420dd6f53e8b84a911 100644 --- a/src/ui/map3D/WebImage.cc +++ b/src/ui/map3D/WebImage.cc @@ -35,11 +35,11 @@ This file is part of the QGROUNDCONTROL project #include WebImage::WebImage() - : state(WebImage::UNINITIALIZED) - , sourceURL("") - , image(0) - , lastReference(0) - , syncFlag(false) + : mState(WebImage::UNINITIALIZED) + , mSourceURL("") + , mImage(0) + , mLastReference(0) + , mSyncFlag(false) { } @@ -47,54 +47,58 @@ WebImage::WebImage() void WebImage::clear(void) { - image.reset(); - sourceURL.clear(); - state = WebImage::UNINITIALIZED; - lastReference = 0; + mImage.reset(); + mSourceURL.clear(); + mState = WebImage::UNINITIALIZED; + mLastReference = 0; } WebImage::State WebImage::getState(void) const { - return state; + return mState; } void WebImage::setState(State state) { - this->state = state; + mState = state; } const QString& WebImage::getSourceURL(void) const { - return sourceURL; + return mSourceURL; } void WebImage::setSourceURL(const QString& url) { - sourceURL = url; + mSourceURL = url; } uchar* WebImage::getImageData(void) const { - return image->scanLine(0); + return mImage->scanLine(0); } bool WebImage::setData(const QByteArray& data) { QImage tempImage; - if (tempImage.loadFromData(data)) { - if (image.isNull()) { - image.reset(new QImage); + if (tempImage.loadFromData(data)) + { + if (mImage.isNull()) + { + mImage.reset(new QImage); } - *image = QGLWidget::convertToGLFormat(tempImage); + *mImage = QGLWidget::convertToGLFormat(tempImage); return true; - } else { + } + else + { return false; } } @@ -103,14 +107,18 @@ bool WebImage::setData(const QString& filename) { QImage tempImage; - if (tempImage.load(filename)) { - if (image.isNull()) { - image.reset(new QImage); + if (tempImage.load(filename)) + { + if (mImage.isNull()) + { + mImage.reset(new QImage); } - *image = QGLWidget::convertToGLFormat(tempImage); + *mImage = QGLWidget::convertToGLFormat(tempImage); return true; - } else { + } + else + { return false; } } @@ -118,41 +126,41 @@ WebImage::setData(const QString& filename) int WebImage::getWidth(void) const { - return image->width(); + return mImage->width(); } int WebImage::getHeight(void) const { - return image->height(); + return mImage->height(); } int WebImage::getByteCount(void) const { - return image->byteCount(); + return mImage->byteCount(); } -ulong +quint64 WebImage::getLastReference(void) const { - return lastReference; + return mLastReference; } void -WebImage::setLastReference(ulong value) +WebImage::setLastReference(quint64 value) { - lastReference = value; + mLastReference = value; } bool WebImage::getSyncFlag(void) const { - return syncFlag; + return mSyncFlag; } void WebImage::setSyncFlag(bool onoff) { - syncFlag = onoff; + mSyncFlag = onoff; } diff --git a/src/ui/map3D/WebImage.h b/src/ui/map3D/WebImage.h index 15c122b21a0dd7276ebf183660525838c72bc9db..6b317dce1d2cb39fde402c05af3a5f9657386a36 100644 --- a/src/ui/map3D/WebImage.h +++ b/src/ui/map3D/WebImage.h @@ -64,18 +64,18 @@ public: int getHeight(void) const; int getByteCount(void) const; - ulong getLastReference(void) const; - void setLastReference(ulong value); + quint64 getLastReference(void) const; + void setLastReference(quint64 value); bool getSyncFlag(void) const; void setSyncFlag(bool onoff); private: - State state; - QString sourceURL; - QScopedPointer image; - ulong lastReference; - bool syncFlag; + State mState; + QString mSourceURL; + QScopedPointer mImage; + quint64 mLastReference; + bool mSyncFlag; }; typedef QSharedPointer WebImagePtr; diff --git a/src/ui/map3D/WebImageCache.cc b/src/ui/map3D/WebImageCache.cc index 0ad66fe7254cc0e06de787722eda286267d79257..42efc5bc59e375f10e5d8a3cd6f6f44575083779 100644 --- a/src/ui/map3D/WebImageCache.cc +++ b/src/ui/map3D/WebImageCache.cc @@ -25,102 +25,129 @@ This file is part of the QGROUNDCONTROL project * @file * @brief Definition of the class WebImageCache. * - * @author Lionel Heng + * @author Lionel Heng * */ #include "WebImageCache.h" +#include #include #include -WebImageCache::WebImageCache(QObject* parent, uint32_t _cacheSize) +WebImageCache::WebImageCache(QObject* parent, int cacheSize) : QObject(parent) - , cacheSize(_cacheSize) - , currentReference(0) - , networkManager(new QNetworkAccessManager) + , mCacheSize(cacheSize) + , mCurrentReference(0) + , mNetworkManager(new QNetworkAccessManager) { - for (uint32_t i = 0; i < cacheSize; ++i) { + for (int i = 0; i < mCacheSize; ++i) + { WebImagePtr image(new WebImage); - webImages.push_back(image); + mWebImages.push_back(image); } - connect(networkManager.data(), SIGNAL(finished(QNetworkReply*)), + connect(mNetworkManager.data(), SIGNAL(finished(QNetworkReply*)), this, SLOT(downloadFinished(QNetworkReply*))); } -QPair +QPair WebImageCache::lookup(const QString& url) { - QPair cacheEntry; + QPair cacheEntry; - for (int32_t i = 0; i < webImages.size(); ++i) { - if (webImages[i]->getState() != WebImage::UNINITIALIZED && - webImages[i]->getSourceURL() == url) { - cacheEntry.first = webImages[i]; + for (int i = 0; i < mWebImages.size(); ++i) + { + WebImagePtr& image = mWebImages[i]; + + if (image->getState() != WebImage::UNINITIALIZED && + image->getSourceURL() == url) + { + cacheEntry.first = image; cacheEntry.second = i; break; } } - if (cacheEntry.first.isNull()) { - for (int32_t i = 0; i < webImages.size(); ++i) { + if (cacheEntry.first.isNull()) + { + for (int i = 0; i < mWebImages.size(); ++i) + { + WebImagePtr& image = mWebImages[i]; + // get uninitialized image - if (webImages[i]->getState() == WebImage::UNINITIALIZED) { - cacheEntry.first = webImages[i]; + if (image->getState() == WebImage::UNINITIALIZED) + { + cacheEntry.first = image; cacheEntry.second = i; break; } // get oldest image - else if (webImages[i]->getState() == WebImage::READY && + else if (image->getState() == WebImage::READY && (cacheEntry.first.isNull() || - webImages[i]->getLastReference() < - cacheEntry.first->getLastReference())) { - cacheEntry.first = webImages[i]; + image->getLastReference() < + cacheEntry.first->getLastReference())) + { + cacheEntry.first = image; cacheEntry.second = i; } } - if (cacheEntry.first.isNull()) { - return qMakePair(WebImagePtr(), -1); - } else { - if (cacheEntry.first->getState() == WebImage::READY) { + if (cacheEntry.first.isNull()) + { + return qMakePair(WebImagePtr(), -1); + } + else + { + if (cacheEntry.first->getState() == WebImage::READY) + { cacheEntry.first->clear(); } cacheEntry.first->setSourceURL(url); - cacheEntry.first->setLastReference(currentReference); - ++currentReference; + cacheEntry.first->setLastReference(mCurrentReference); + ++mCurrentReference; cacheEntry.first->setState(WebImage::REQUESTED); - if (url.left(4).compare("http") == 0) { - networkManager->get(QNetworkRequest(QUrl(url))); - } else { - if (cacheEntry.first->setData(url)) { + if (url.left(4).compare("http") == 0) + { + mNetworkManager->get(QNetworkRequest(QUrl(url))); + } + else + { + if (cacheEntry.first->setData(url)) + { cacheEntry.first->setSyncFlag(true); cacheEntry.first->setState(WebImage::READY); - } else { + } + else + { cacheEntry.first->setState(WebImage::UNINITIALIZED); } } return cacheEntry; } - } else { - if (cacheEntry.first->getState() == WebImage::READY) { - cacheEntry.first->setLastReference(currentReference); - ++currentReference; + } + else + { + if (cacheEntry.first->getState() == WebImage::READY) + { + cacheEntry.first->setLastReference(mCurrentReference); + ++mCurrentReference; return cacheEntry; - } else { + } + else + { return qMakePair(WebImagePtr(), -1); } } } WebImagePtr -WebImageCache::at(int32_t index) const +WebImageCache::at(int index) const { - return webImages[index]; + return mWebImages[index]; } void @@ -128,17 +155,21 @@ WebImageCache::downloadFinished(QNetworkReply* reply) { reply->deleteLater(); - if (reply->error() != QNetworkReply::NoError) { + if (reply->error() != QNetworkReply::NoError) + { return; } QVariant attribute = reply->attribute(QNetworkRequest::RedirectionTargetAttribute); - if (attribute.isValid()) { + if (attribute.isValid()) + { return; } WebImagePtr image; - foreach(image, webImages) { - if (reply->url().toString() == image->getSourceURL()) { + foreach(image, mWebImages) + { + if (reply->url().toString() == image->getSourceURL()) + { image->setData(reply->readAll()); image->setSyncFlag(true); image->setState(WebImage::READY); diff --git a/src/ui/map3D/WebImageCache.h b/src/ui/map3D/WebImageCache.h index d482d717a60b2338e5a2f20e1e8beda680211759..136800a5545dcb653b69beea6f2841e3c0e32aaf 100644 --- a/src/ui/map3D/WebImageCache.h +++ b/src/ui/map3D/WebImageCache.h @@ -25,7 +25,7 @@ This file is part of the QGROUNDCONTROL project * @file * @brief Definition of the class WebImageCache. * - * @author Lionel Heng + * @author Lionel Heng * */ @@ -43,22 +43,22 @@ class WebImageCache : public QObject Q_OBJECT public: - WebImageCache(QObject* parent, uint32_t cacheSize); + WebImageCache(QObject* parent, int cacheSize); - QPair lookup(const QString& url); + QPair lookup(const QString& url); - WebImagePtr at(int32_t index) const; + WebImagePtr at(int index) const; private Q_SLOTS: void downloadFinished(QNetworkReply* reply); private: - uint32_t cacheSize; + int mCacheSize; - QVector webImages; - uint64_t currentReference; + QVector mWebImages; + quint64 mCurrentReference; - QScopedPointer networkManager; + QScopedPointer mNetworkManager; }; #endif // WEBIMAGECACHE_H