From fdc8d522c7e82c95b967b77e7bf7de20cfc6f81e Mon Sep 17 00:00:00 2001 From: hengli Date: Wed, 27 Oct 2010 18:50:36 +0200 Subject: [PATCH 1/2] Added support to read in imagery data from disk storage. --- src/ui/map3D/Imagery.cc | 109 +++++++++++++++++++++++++++++++----------- src/ui/map3D/Imagery.h | 8 ++-- src/ui/map3D/QMap3DWidget.cc | 14 +++++- src/ui/map3D/WebImage.cc | 28 ++++++++++- src/ui/map3D/WebImage.h | 3 +- src/ui/map3D/WebImageCache.cc | 17 ++++++- 6 files changed, 144 insertions(+), 35 deletions(-) diff --git a/src/ui/map3D/Imagery.cc b/src/ui/map3D/Imagery.cc index 714fb65..a2dbb42 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 const double WGS84_A = 6378137.0; @@ -65,7 +66,8 @@ Imagery::prefetch2D(double windowWidth, double windowHeight, const QString& utmZone) { double tileResolution; - if (currentImageryType == SATELLITE) + if (currentImageryType == GOOGLE_SATELLITE || + currentImageryType == GOOGLE_MAP) { tileResolution = 1.0; while (tileResolution * 3.0 / 2.0 < 1.0 / zoom) @@ -77,6 +79,10 @@ Imagery::prefetch2D(double windowWidth, double windowHeight, tileResolution = 512.0; } } + else if (currentImageryType == SWISSTOPO_SATELLITE) + { + tileResolution = 0.25; + } int32_t minTileX, minTileY, maxTileX, maxTileY; int32_t zoomLevel; @@ -92,7 +98,7 @@ Imagery::prefetch2D(double windowWidth, double windowHeight, { for (int32_t c = minTileX; c <= maxTileX; ++c) { - QString url = getTileURL(c, r, zoomLevel); + QString url = getTileLocation(c, r, zoomLevel, tileResolution); TexturePtr t = textureCache->get(url); } @@ -106,7 +112,8 @@ Imagery::draw2D(double windowWidth, double windowHeight, const QString& utmZone) { double tileResolution; - if (currentImageryType == SATELLITE) + if (currentImageryType == GOOGLE_SATELLITE || + currentImageryType == GOOGLE_MAP) { tileResolution = 1.0; while (tileResolution * 3.0 / 2.0 < 1.0 / zoom) @@ -118,6 +125,10 @@ Imagery::draw2D(double windowWidth, double windowHeight, tileResolution = 512.0; } } + else if (currentImageryType == SWISSTOPO_SATELLITE) + { + tileResolution = 0.25; + } int32_t minTileX, minTileY, maxTileX, maxTileY; int32_t zoomLevel; @@ -133,7 +144,7 @@ Imagery::draw2D(double windowWidth, double windowHeight, { for (int32_t c = minTileX; c <= maxTileX; ++c) { - QString tileURL = getTileURL(c, r, zoomLevel); + 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); @@ -170,7 +181,7 @@ Imagery::prefetch3D(double radius, double tileResolution, { for (int32_t c = minTileX; c <= maxTileX; ++c) { - QString url = getTileURL(c, r, zoomLevel); + QString url = getTileLocation(c, r, zoomLevel, tileResolution); TexturePtr t = textureCache->get(url); } @@ -197,7 +208,7 @@ Imagery::draw3D(double radius, double tileResolution, { for (int32_t c = minTileX; c <= maxTileX; ++c) { - QString tileURL = getTileURL(c, r, zoomLevel); + 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); @@ -228,20 +239,37 @@ Imagery::imageBounds(int32_t tileX, int32_t tileY, double tileResolution, double& x1, double& y1, double& x2, double& y2, double& x3, double& y3, double& x4, double& y4) const { - int32_t zoomLevel = MAX_ZOOM_LEVEL - static_cast(rint(log2(tileResolution))); - int32_t numTiles = static_cast(exp2(static_cast(zoomLevel))); + if (currentImageryType == GOOGLE_MAP || + currentImageryType == GOOGLE_SATELLITE) + { + int32_t zoomLevel = MAX_ZOOM_LEVEL - static_cast(rint(log2(tileResolution))); + int32_t numTiles = static_cast(exp2(static_cast(zoomLevel))); - double lon1 = tileXToLongitude(tileX, numTiles); - double lon2 = tileXToLongitude(tileX + 1, numTiles); + double lon1 = tileXToLongitude(tileX, numTiles); + double lon2 = tileXToLongitude(tileX + 1, numTiles); - double lat1 = tileYToLatitude(tileY, numTiles); - double lat2 = tileYToLatitude(tileY + 1, numTiles); + double lat1 = tileYToLatitude(tileY, numTiles); + double lat2 = tileYToLatitude(tileY + 1, numTiles); - QString utmZone; - LLtoUTM(lat1, lon1, x1, y1, utmZone); - LLtoUTM(lat1, lon2, x2, y2, utmZone); - LLtoUTM(lat2, lon2, x3, y3, utmZone); - LLtoUTM(lat2, lon1, x4, y4, utmZone); + QString utmZone; + LLtoUTM(lat1, lon1, x1, y1, utmZone); + LLtoUTM(lat1, lon2, x2, y2, utmZone); + LLtoUTM(lat2, lon2, x3, y3, utmZone); + LLtoUTM(lat2, lon1, x4, y4, utmZone); + } + else if (currentImageryType == SWISSTOPO_SATELLITE) + { + double utmMultiplier = tileResolution * 200.0; + double minX = tileX * utmMultiplier; + double maxX = minX + utmMultiplier; + double minY = tileY * utmMultiplier; + double maxY = minY + utmMultiplier; + + x1 = maxX; y1 = minY; + x2 = maxX; y2 = maxY; + x3 = minX; y3 = maxY; + x4 = minX; y4 = minY; + } } void @@ -254,15 +282,29 @@ Imagery::tileBounds(double tileResolution, { double centerUtmX = (maxUtmX - minUtmX) / 2.0 + minUtmX; double centerUtmY = (maxUtmY - minUtmY) / 2.0 + minUtmY; - int32_t centerTileX, centerTileY; - UTMtoTile(minUtmX, minUtmY, utmZone, tileResolution, - minTileX, maxTileY, zoomLevel); - UTMtoTile(centerUtmX, centerUtmY, utmZone, tileResolution, - centerTileX, centerTileY, zoomLevel); - UTMtoTile(maxUtmX, maxUtmY, utmZone, tileResolution, - maxTileX, minTileY, zoomLevel); + if (currentImageryType == GOOGLE_MAP || + currentImageryType == 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) + { + double utmMultiplier = tileResolution * 200; + + minTileX = static_cast(floor(minUtmX / utmMultiplier)); + minTileY = static_cast(floor(minUtmY / utmMultiplier)); + centerTileX = static_cast(floor(centerUtmX / utmMultiplier)); + centerTileY = static_cast(floor(centerUtmY / utmMultiplier)); + maxTileX = static_cast(floor(maxUtmX / utmMultiplier)); + maxTileY = static_cast(floor(maxUtmY / utmMultiplier)); + } if (maxTileX - minTileX + 1 > 14) { @@ -513,20 +555,33 @@ Imagery::UTMtoLL(double utmNorthing, double utmEasting, const QString& utmZone, } QString -Imagery::getTileURL(int32_t tileX, int32_t tileY, int32_t zoomLevel) const +Imagery::getTileLocation(int32_t tileX, int32_t tileY, int32_t zoomLevel, + double tileResolution) const { std::ostringstream oss; switch (currentImageryType) { - case MAP: + case GOOGLE_MAP: oss << "http://mt0.google.com/vt/lyrs=m@120&x=" << tileX << "&y=" << tileY << "&z=" << zoomLevel; break; - case SATELLITE: + case GOOGLE_SATELLITE: 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/" << tileX + << "/tile-"; + if (tileResolution < 1.0) + { + oss << std::fixed << std::setprecision(2) << tileResolution; + } + else + { + oss << static_cast(rint(tileResolution)); + } + oss << "-" << tileX << "-" << tileY << ".jpg"; default: {}; } diff --git a/src/ui/map3D/Imagery.h b/src/ui/map3D/Imagery.h index bcfe10b..22008e0 100644 --- a/src/ui/map3D/Imagery.h +++ b/src/ui/map3D/Imagery.h @@ -43,8 +43,9 @@ public: enum ImageryType { - MAP = 0, - SATELLITE = 1 + GOOGLE_MAP = 0, + GOOGLE_SATELLITE = 1, + SWISSTOPO_SATELLITE = 2 }; void setImageryType(ImageryType type); @@ -100,7 +101,8 @@ private: void UTMtoLL(double utmNorthing, double utmEasting, const QString& utmZone, double& latitude, double& longitude) const; - QString getTileURL(int32_t tileX, int32_t tileY, int32_t zoomLevel) const; + QString getTileLocation(int32_t tileX, int32_t tileY, int32_t zoomLevel, + double tileResolution) const; ImageryType currentImageryType; diff --git a/src/ui/map3D/QMap3DWidget.cc b/src/ui/map3D/QMap3DWidget.cc index 830c7b8..51ed073 100644 --- a/src/ui/map3D/QMap3DWidget.cc +++ b/src/ui/map3D/QMap3DWidget.cc @@ -95,6 +95,7 @@ QMap3DWidget::buildLayout(void) imageryComboBox->addItem("None"); imageryComboBox->addItem("Map (Google)"); imageryComboBox->addItem("Satellite (Google)"); + imageryComboBox->addItem("Satellite (Swisstopo)"); QPushButton* recenterButton = new QPushButton(this); recenterButton->setText("Recenter Camera"); @@ -536,11 +537,15 @@ QMap3DWidget::showImagery(const QString& text) { if (text.compare("Map (Google)") == 0) { - imagery->setImageryType(Imagery::MAP); + imagery->setImageryType(Imagery::GOOGLE_MAP); } else if (text.compare("Satellite (Google)") == 0) { - imagery->setImageryType(Imagery::SATELLITE); + imagery->setImageryType(Imagery::GOOGLE_SATELLITE); + } + else if (text.compare("Satellite (Swisstopo)") == 0) + { + imagery->setImageryType(Imagery::SWISSTOPO_SATELLITE); } displayImagery = true; } @@ -682,6 +687,11 @@ QMap3DWidget::drawImagery(double originX, double originY, double originZ, { minResolution = 0.5; } + else if (imageryComboBox->currentText().compare("Satellite (Swisstopo)") == 0) + { + minResolution = 0.25; + maxResolution = 0.25; + } double resolution = minResolution; while (resolution * 2.0 < centerResolution) diff --git a/src/ui/map3D/WebImage.cc b/src/ui/map3D/WebImage.cc index be97fa3..df11673 100644 --- a/src/ui/map3D/WebImage.cc +++ b/src/ui/map3D/WebImage.cc @@ -83,7 +83,7 @@ WebImage::getData(void) const return image->scanLine(0); } -void +bool WebImage::setData(const QByteArray& data) { QImage tempImage; @@ -94,10 +94,36 @@ WebImage::setData(const QByteArray& data) image.reset(new QImage); } *image = QGLWidget::convertToGLFormat(tempImage); + + return true; } else { qDebug() << "# WARNING: cannot load image data for" << sourceURL; + + return false; + } +} + +bool +WebImage::setData(const QString& filename) +{ + QImage tempImage; + if (tempImage.load(filename)) + { + if (image.isNull()) + { + image.reset(new QImage); + } + *image = QGLWidget::convertToGLFormat(tempImage); + + return true; + } + else + { + qDebug() << "# WARNING: cannot load image data for" << filename; + + return false; } } diff --git a/src/ui/map3D/WebImage.h b/src/ui/map3D/WebImage.h index ac601dc..02321a6 100644 --- a/src/ui/map3D/WebImage.h +++ b/src/ui/map3D/WebImage.h @@ -58,7 +58,8 @@ public: void setSourceURL(const QString& url); const uint8_t* getData(void) const; - void setData(const QByteArray& data); + bool setData(const QByteArray& data); + bool setData(const QString& filename); int32_t getWidth(void) const; int32_t getHeight(void) const; diff --git a/src/ui/map3D/WebImageCache.cc b/src/ui/map3D/WebImageCache.cc index 77e3f71..aca9e4f 100644 --- a/src/ui/map3D/WebImageCache.cc +++ b/src/ui/map3D/WebImageCache.cc @@ -104,7 +104,22 @@ WebImageCache::lookup(const QString& url) ++currentReference; cacheEntry.first->setState(WebImage::REQUESTED); - networkManager->get(QNetworkRequest(QUrl(url))); + if (url.left(4).compare("http") == 0) + { + networkManager->get(QNetworkRequest(QUrl(url))); + } + else + { + if (cacheEntry.first->setData(url)) + { + cacheEntry.first->setSyncFlag(true); + cacheEntry.first->setState(WebImage::READY); + } + else + { + cacheEntry.first->setState(WebImage::UNINITIALIZED); + } + } return cacheEntry; } From 1dc379f0796210886fbd34e0806df43d3b65ff4a Mon Sep 17 00:00:00 2001 From: Lionel Heng Date: Wed, 27 Oct 2010 23:19:57 +0200 Subject: [PATCH 2/2] Fixed coordinate bug in imagery. --- src/ui/map3D/Imagery.cc | 16 ++++++++-------- src/ui/map3D/Q3DWidget.cc | 8 +++++--- src/ui/map3D/WebImage.cc | 5 ----- 3 files changed, 13 insertions(+), 16 deletions(-) diff --git a/src/ui/map3D/Imagery.cc b/src/ui/map3D/Imagery.cc index a2dbb42..8c2f9f3 100644 --- a/src/ui/map3D/Imagery.cc +++ b/src/ui/map3D/Imagery.cc @@ -298,12 +298,12 @@ Imagery::tileBounds(double tileResolution, { double utmMultiplier = tileResolution * 200; - minTileX = static_cast(floor(minUtmX / utmMultiplier)); - minTileY = static_cast(floor(minUtmY / utmMultiplier)); - centerTileX = static_cast(floor(centerUtmX / utmMultiplier)); - centerTileY = static_cast(floor(centerUtmY / utmMultiplier)); - maxTileX = static_cast(floor(maxUtmX / utmMultiplier)); - maxTileY = static_cast(floor(maxUtmY / utmMultiplier)); + minTileX = static_cast(rint(minUtmX / utmMultiplier)); + minTileY = static_cast(rint(minUtmY / utmMultiplier)); + centerTileX = static_cast(rint(centerUtmX / utmMultiplier)); + centerTileY = static_cast(rint(centerUtmY / utmMultiplier)); + maxTileX = static_cast(rint(maxUtmX / utmMultiplier)); + maxTileY = static_cast(rint(maxUtmY / utmMultiplier)); } if (maxTileX - minTileX + 1 > 14) @@ -571,7 +571,7 @@ Imagery::getTileLocation(int32_t tileX, int32_t tileY, int32_t zoomLevel, << "&y=" << tileY << "&z=" << zoomLevel; break; case SWISSTOPO_SATELLITE: - oss << "../map/eth_zurich_swissimage_025/200/color/" << tileX + oss << "../map/eth_zurich_swissimage_025/200/color/" << tileY << "/tile-"; if (tileResolution < 1.0) { @@ -581,7 +581,7 @@ Imagery::getTileLocation(int32_t tileX, int32_t tileY, int32_t zoomLevel, { oss << static_cast(rint(tileResolution)); } - oss << "-" << tileX << "-" << tileY << ".jpg"; + oss << "-" << tileY << "-" << tileX << ".jpg"; default: {}; } diff --git a/src/ui/map3D/Q3DWidget.cc b/src/ui/map3D/Q3DWidget.cc index c3a7370..be4f0dd 100755 --- a/src/ui/map3D/Q3DWidget.cc +++ b/src/ui/map3D/Q3DWidget.cc @@ -232,7 +232,7 @@ Q3DWidget::userTimer(void) { if (timerFunc) { - timerFunc(timerFuncData); + timerFunc(timerFuncData); } } @@ -356,7 +356,6 @@ Q3DWidget::getMouseY(void) return mapFromGlobal(cursor().pos()).y(); } - void Q3DWidget::rotateCamera(float dx, float dy) { @@ -858,9 +857,12 @@ Q3DWidget::timerEvent(QTimerEvent* event) } void -Q3DWidget::closeEvent(QCloseEvent *) +Q3DWidget::closeEvent(QCloseEvent* event) { // exit application + timer.stop(); + + event->accept(); } void diff --git a/src/ui/map3D/WebImage.cc b/src/ui/map3D/WebImage.cc index df11673..a5c1e88 100644 --- a/src/ui/map3D/WebImage.cc +++ b/src/ui/map3D/WebImage.cc @@ -31,7 +31,6 @@ This file is part of the QGROUNDCONTROL project #include "WebImage.h" -#include #include WebImage::WebImage() @@ -99,8 +98,6 @@ WebImage::setData(const QByteArray& data) } else { - qDebug() << "# WARNING: cannot load image data for" << sourceURL; - return false; } } @@ -121,8 +118,6 @@ WebImage::setData(const QString& filename) } else { - qDebug() << "# WARNING: cannot load image data for" << filename; - return false; } }