Browse Source

Fixes for Linux and Android

Fixing QmlObjectListModel usage bug
QGC4.4
dogmaphobic 9 years ago
parent
commit
04ea3c19ed
  1. 3
      src/QtLocationPlugin/QGCMapEngine.cpp
  2. 13
      src/QtLocationPlugin/QGCMapEngineData.h
  3. 8
      src/QtLocationPlugin/QGCMapTileSet.cpp
  4. 4
      src/QtLocationPlugin/QGCTileCacheWorker.cpp
  5. 4
      src/QtLocationPlugin/QGeoTiledMappingManagerEngineQGC.cpp
  6. 63
      src/QtLocationPlugin/QMLControl/OfflineMap.qml
  7. 16
      src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc
  8. 1
      src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h

3
src/QtLocationPlugin/QGCMapEngine.cpp

@ -114,7 +114,7 @@ destroyMapEngine()
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QGCMapEngine::QGCMapEngine() QGCMapEngine::QGCMapEngine()
: _urlFactory(new UrlFactory::UrlFactory()) : _urlFactory(new UrlFactory())
#ifdef WE_ARE_KOSHER #ifdef WE_ARE_KOSHER
//-- TODO: Get proper version //-- TODO: Get proper version
#if defined Q_OS_MAC #if defined Q_OS_MAC
@ -173,6 +173,7 @@ QGCMapEngine::init()
if(!_cachePath.isEmpty()) { if(!_cachePath.isEmpty()) {
_cacheFile = kDbFileName; _cacheFile = kDbFileName;
_worker.setDatabaseFile(_cachePath + "/" + _cacheFile); _worker.setDatabaseFile(_cachePath + "/" + _cacheFile);
qDebug() << "Map Cache in:" << _cachePath << "/" << _cacheFile;
} else { } else {
qCritical() << "Could not find suitable map cache directory."; qCritical() << "Could not find suitable map cache directory.";
} }

13
src/QtLocationPlugin/QGCMapEngineData.h

@ -42,9 +42,8 @@ This file is part of the QGROUNDCONTROL project
class QGCCachedTileSet; class QGCCachedTileSet;
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
class QGCTile : public QObject class QGCTile
{ {
Q_OBJECT
public: public:
QGCTile() QGCTile()
: _x(0) : _x(0)
@ -55,16 +54,6 @@ public:
{ {
} }
QGCTile(const QGCTile& other)
: _x(other.x())
, _y(other.y())
, _z(other.z())
, _set(other.set())
, _hash(other.hash())
, _type(other.type())
{
}
enum TyleState { enum TyleState {
StatePending = 0, StatePending = 0,
StateDownloading, StateDownloading,

8
src/QtLocationPlugin/QGCMapTileSet.cpp

@ -115,8 +115,10 @@ QGCCachedTileSet::savedSizeStr()
QString QString
QGCCachedTileSet::downloadStatus() QGCCachedTileSet::downloadStatus()
{ {
//-- Default size has no estimage. If complete, show only total size as well. if(_defaultSet) {
if(_defaultSet || _numTiles == _savedTiles) { return tilesSizeStr();
}
if(_numTiles == _savedTiles) {
return savedSizeStr(); return savedSizeStr();
} else { } else {
return savedSizeStr() + " / " + tilesSizeStr(); return savedSizeStr() + " / " + tilesSizeStr();
@ -222,7 +224,7 @@ void QGCCachedTileSet::_prepareDownload()
connect(reply, &QNetworkReply::finished, this, &QGCCachedTileSet::_networkReplyFinished); connect(reply, &QNetworkReply::finished, this, &QGCCachedTileSet::_networkReplyFinished);
connect(reply, static_cast<void (QNetworkReply::*)(QNetworkReply::NetworkError)>(&QNetworkReply::error), this, &QGCCachedTileSet::_networkReplyError); connect(reply, static_cast<void (QNetworkReply::*)(QNetworkReply::NetworkError)>(&QNetworkReply::error), this, &QGCCachedTileSet::_networkReplyError);
_replies.insert(tile->hash(), reply); _replies.insert(tile->hash(), reply);
tile->deleteLater(); delete tile;
//-- Refill queue if running low //-- Refill queue if running low
if(!_batchRequested && !_noMoreTiles && _tilesToDownload.count() < (QGCMapEngine::concurrentDownloads(_type) * 10)) { if(!_batchRequested && !_noMoreTiles && _tilesToDownload.count() < (QGCMapEngine::concurrentDownloads(_type) * 10)) {
//-- Request new batch of tiles //-- Request new batch of tiles

4
src/QtLocationPlugin/QGCTileCacheWorker.cpp

@ -352,9 +352,8 @@ QGCCacheWorker::_getTileSets(QGCMapTask* mtask)
void void
QGCCacheWorker::_updateSetTotals(QGCCachedTileSet* set) QGCCacheWorker::_updateSetTotals(QGCCachedTileSet* set)
{ {
_updateTotals();
if(set->defaultSet()) { if(set->defaultSet()) {
//-- Default Set is already computed _updateTotals();
set->setSavedTiles(_totalCount); set->setSavedTiles(_totalCount);
set->setSavedSize(_totalSize); set->setSavedSize(_totalSize);
set->setNumTiles(_defaultCount); set->setNumTiles(_defaultCount);
@ -362,7 +361,6 @@ QGCCacheWorker::_updateSetTotals(QGCCachedTileSet* set)
return; return;
} }
QSqlQuery subquery(*_db); QSqlQuery subquery(*_db);
//-- Count everythin for Default Set
QString sq = QString("SELECT COUNT(size), SUM(size) FROM Tiles A INNER JOIN SetTiles B on A.tileID = B.tileID WHERE B.setID = %1").arg(set->id()); QString sq = QString("SELECT COUNT(size), SUM(size) FROM Tiles A INNER JOIN SetTiles B on A.tileID = B.tileID WHERE B.setID = %1").arg(set->id());
if(subquery.exec(sq)) { if(subquery.exec(sq)) {
if(subquery.next()) { if(subquery.next()) {

4
src/QtLocationPlugin/QGeoTiledMappingManagerEngineQGC.cpp

@ -226,7 +226,9 @@ QGeoTiledMappingManagerEngineQGC::_setCache(const QVariantMap &parameters)
QGeoTileCache* pTileCache = createTileCacheWithDir(cacheDir); QGeoTileCache* pTileCache = createTileCacheWithDir(cacheDir);
if(pTileCache) if(pTileCache)
{ {
pTileCache->setMaxDiskUsage(1); //-- We're basically telling it to use 1kb of disk for cache. It doesn't like
// values smaller than that and I could not find a way to make it NOT cache.
pTileCache->setMaxDiskUsage(1024);
pTileCache->setMaxMemoryUsage(memLimit); pTileCache->setMaxMemoryUsage(memLimit);
} }
} }

63
src/QtLocationPlugin/QMLControl/OfflineMap.qml

@ -268,6 +268,10 @@ Rectangle {
handleChanges() handleChanges()
checkSanity() checkSanity()
} }
// Used to make pinch zoom work
MouseArea {
anchors.fill: parent
}
} }
Rectangle { Rectangle {
width: ScreenTools.defaultFontPixelHeight * 16 width: ScreenTools.defaultFontPixelHeight * 16
@ -317,7 +321,7 @@ Rectangle {
Row { Row {
id: _controlRow id: _controlRow
anchors.centerIn: parent anchors.centerIn: parent
spacing: ScreenTools.defaultFontPixelWidth * 2 spacing: ScreenTools.defaultFontPixelWidth * 0.5
Rectangle { Rectangle {
height: _zoomRow.height + ScreenTools.defaultFontPixelHeight * 1.5 height: _zoomRow.height + ScreenTools.defaultFontPixelHeight * 1.5
width: _zoomRow.width + ScreenTools.defaultFontPixelWidth width: _zoomRow.width + ScreenTools.defaultFontPixelWidth
@ -362,7 +366,7 @@ Rectangle {
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
style: SliderStyle { style: SliderStyle {
groove: Rectangle { groove: Rectangle {
implicitWidth: ScreenTools.defaultFontPixelWidth * 16 implicitWidth: ScreenTools.defaultFontPixelWidth * 12
implicitHeight: 4 implicitHeight: 4
color: "gray" color: "gray"
radius: 4 radius: 4
@ -372,8 +376,8 @@ Rectangle {
color: control.pressed ? "white" : "lightgray" color: control.pressed ? "white" : "lightgray"
border.color: "gray" border.color: "gray"
border.width: 2 border.width: 2
implicitWidth: 30 implicitWidth: ScreenTools.isAndroid ? 60 : 30
implicitHeight: 30 implicitHeight: ScreenTools.isAndroid ? 60 : 30
radius: 10 radius: 10
Label { Label {
text: _slider0.value text: _slider0.value
@ -426,7 +430,7 @@ Rectangle {
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
style: SliderStyle { style: SliderStyle {
groove: Rectangle { groove: Rectangle {
implicitWidth: ScreenTools.defaultFontPixelWidth * 16 implicitWidth: ScreenTools.defaultFontPixelWidth * 12
implicitHeight: 4 implicitHeight: 4
color: "gray" color: "gray"
radius: 4 radius: 4
@ -436,8 +440,8 @@ Rectangle {
color: control.pressed ? "white" : "lightgray" color: control.pressed ? "white" : "lightgray"
border.color: "gray" border.color: "gray"
border.width: 2 border.width: 2
implicitWidth: 30 implicitWidth: ScreenTools.isAndroid ? 60 : 30
implicitHeight: 30 implicitHeight: ScreenTools.isAndroid ? 60 : 30
radius: 10 radius: 10
Label { Label {
text: _slider1.value text: _slider1.value
@ -504,7 +508,7 @@ Rectangle {
} }
QGCTextField { QGCTextField {
id: setName id: setName
width: ScreenTools.defaultFontPixelWidth * 30 width: ScreenTools.defaultFontPixelWidth * 24
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
} }
} }
@ -519,7 +523,7 @@ Rectangle {
QGCTextField { QGCTextField {
id: setDescription id: setDescription
text: "Description" text: "Description"
width: ScreenTools.defaultFontPixelWidth * 30 width: ScreenTools.defaultFontPixelWidth * 24
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
} }
} }
@ -533,7 +537,7 @@ Rectangle {
} }
QGCComboBox { QGCComboBox {
id: mapCombo id: mapCombo
width: ScreenTools.defaultFontPixelWidth * 30 width: ScreenTools.defaultFontPixelWidth * 24
model: QGroundControl.mapEngineManager.mapList model: QGroundControl.mapEngineManager.mapList
onActivated: { onActivated: {
mapType = textAt(index) mapType = textAt(index)
@ -554,7 +558,7 @@ Rectangle {
} }
Item { Item {
height: 1 height: 1
width: ScreenTools.defaultFontPixelWidth * 2 width: ScreenTools.defaultFontPixelWidth * 1.5
} }
Column { Column {
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
@ -567,7 +571,7 @@ Rectangle {
if(QGroundControl.mapEngineManager.findName(setName.text)) { if(QGroundControl.mapEngineManager.findName(setName.text)) {
duplicateName.visible = true duplicateName.visible = true
} else { } else {
/* Broken in Qt 5.5.1 /* This does not work if hosted by QQuickWidget. Waiting until we're 100% QtQuick
var mapImage var mapImage
_map.grabToImage(function(result) { mapImage = result; }) _map.grabToImage(function(result) { mapImage = result; })
QGroundControl.mapEngineManager.startDownload(setName.text, setDescription.text, mapType, mapImage); QGroundControl.mapEngineManager.startDownload(setName.text, setDescription.text, mapType, mapImage);
@ -612,7 +616,7 @@ Rectangle {
width: parent.width width: parent.width
spacing: ScreenTools.defaultFontPixelHeight spacing: ScreenTools.defaultFontPixelHeight
Item { Item {
height: ScreenTools.defaultFontPixelHeight height: ScreenTools.defaultFontPixelHeight * 0.5
width: 1 width: 1
} }
Rectangle { Rectangle {
@ -624,7 +628,7 @@ Rectangle {
QGCLabel { QGCLabel {
id: nameLabel id: nameLabel
text: _offlineMapRoot._currentSelection ? _offlineMapRoot._currentSelection.name : "" text: _offlineMapRoot._currentSelection ? _offlineMapRoot._currentSelection.name : ""
font.pixelSize: ScreenTools.largeFontPixelSize font.pixelSize: ScreenTools.isAndroid ? ScreenTools.mediumFontPixelSize : ScreenTools.largeFontPixelSize
anchors.centerIn: parent anchors.centerIn: parent
} }
} }
@ -684,13 +688,13 @@ Rectangle {
text: _offlineMapRoot._currentSelection ? _offlineMapRoot._currentSelection.numTilesStr : "" text: _offlineMapRoot._currentSelection ? _offlineMapRoot._currentSelection.numTilesStr : ""
} }
QGCLabel { QGCLabel {
text: isDefaultSet ? "Total Size:" : "Downloaded Size:" text: isDefaultSet ? "Total Size (All Sets):" : "Downloaded Size:"
} }
QGCLabel { QGCLabel {
text: _offlineMapRoot._currentSelection ? _offlineMapRoot._currentSelection.savedSizeStr : "" text: _offlineMapRoot._currentSelection ? _offlineMapRoot._currentSelection.savedSizeStr : ""
} }
QGCLabel { QGCLabel {
text: isDefaultSet ? "Total Count:" : "Downloaded Count:" text: isDefaultSet ? "Total Count (All Sets):" : "Downloaded Count:"
} }
QGCLabel { QGCLabel {
text: _offlineMapRoot._currentSelection ? _offlineMapRoot._currentSelection.savedTilesStr : "" text: _offlineMapRoot._currentSelection ? _offlineMapRoot._currentSelection.savedTilesStr : ""
@ -706,18 +710,13 @@ Rectangle {
} }
} }
Item { Item {
height: ScreenTools.defaultFontPixelHeight height: ScreenTools.defaultFontPixelHeight * 0.5
width: 1 width: 1
} }
Row { Row {
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
spacing: ScreenTools.defaultFontPixelWidth spacing: ScreenTools.defaultFontPixelWidth
QGCButton { QGCButton {
text: "Back"
width: ScreenTools.defaultFontPixelWidth * 18
onClicked: showList()
}
QGCButton {
width: ScreenTools.defaultFontPixelWidth * 18 width: ScreenTools.defaultFontPixelWidth * 18
text: "Delete" text: "Delete"
enabled: _offlineMapRoot._currentSelection && (!_offlineMapRoot._currentSelection.deleting) enabled: _offlineMapRoot._currentSelection && (!_offlineMapRoot._currentSelection.deleting)
@ -772,6 +771,11 @@ Rectangle {
_offlineMapRoot._currentSelection.cancelDownloadTask() _offlineMapRoot._currentSelection.cancelDownloadTask()
} }
} }
QGCButton {
text: "Back"
width: ScreenTools.defaultFontPixelWidth * 18
onClicked: showList()
}
} }
} }
} }
@ -787,7 +791,7 @@ Rectangle {
if(_optionsView.visible) { if(_optionsView.visible) {
mapBoxToken.text = QGroundControl.mapEngineManager.mapboxToken mapBoxToken.text = QGroundControl.mapEngineManager.mapboxToken
maxCacheSize.text = QGroundControl.mapEngineManager.maxDiskCache maxCacheSize.text = QGroundControl.mapEngineManager.maxDiskCache
maxCacheMemSize.text = QGroundControl.mapEngineManager.maxDiskCache maxCacheMemSize.text = QGroundControl.mapEngineManager.maxMemCache
} }
} }
Column { Column {
@ -806,8 +810,8 @@ Rectangle {
QGCLabel { QGCLabel {
id: optionsLabel id: optionsLabel
text: "Offline Map Options" text: "Offline Map Options"
font.pixelSize: ScreenTools.largeFontPixelSize font.pixelSize: ScreenTools.isAndroid ? ScreenTools.mediumFontPixelSize : ScreenTools.largeFontPixelSize
anchors.centerIn: parent anchors.centerIn: parent
} }
} }
Rectangle { Rectangle {
@ -829,7 +833,7 @@ Rectangle {
} }
QGCTextField { QGCTextField {
id: maxCacheSize id: maxCacheSize
maximumLength: 256 maximumLength: 6
inputMethodHints: Qt.ImhDigitsOnly inputMethodHints: Qt.ImhDigitsOnly
validator: IntValidator {bottom: 1; top: 262144;} validator: IntValidator {bottom: 1; top: 262144;}
} }
@ -838,7 +842,7 @@ Rectangle {
} }
QGCTextField { QGCTextField {
id: maxCacheMemSize id: maxCacheMemSize
maximumLength: 256 maximumLength: 4
inputMethodHints: Qt.ImhDigitsOnly inputMethodHints: Qt.ImhDigitsOnly
validator: IntValidator {bottom: 1; top: 4096;} validator: IntValidator {bottom: 1; top: 4096;}
} }
@ -865,7 +869,7 @@ Rectangle {
id: mapBoxToken id: mapBoxToken
Layout.fillWidth: true Layout.fillWidth: true
maximumLength: 256 maximumLength: 256
implicitWidth : ScreenTools.defaultFontPixelHeight * 30 implicitWidth : ScreenTools.defaultFontPixelWidth * 30
} }
Item { Item {
Layout.columnSpan: 2 Layout.columnSpan: 2
@ -886,6 +890,9 @@ Rectangle {
text: "Save" text: "Save"
width: ScreenTools.defaultFontPixelWidth * 18 width: ScreenTools.defaultFontPixelWidth * 18
onClicked: { onClicked: {
QGroundControl.mapEngineManager.mapboxToken = mapBoxToken.text
QGroundControl.mapEngineManager.maxDiskCache = parseInt(maxCacheSize.text)
QGroundControl.mapEngineManager.maxMemCache = parseInt(maxCacheMemSize.text)
showList() showList()
} }
} }

16
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc

@ -54,7 +54,7 @@ QGCMapEngineManager::QGCMapEngineManager(QGCApplication* app)
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QGCMapEngineManager::~QGCMapEngineManager() QGCMapEngineManager::~QGCMapEngineManager()
{ {
//_clearTileSets(); _tileSets.clear();
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
@ -120,7 +120,7 @@ void
QGCMapEngineManager::loadTileSets() QGCMapEngineManager::loadTileSets()
{ {
if(_tileSets.count()) { if(_tileSets.count()) {
_clearTileSets(); _tileSets.clear();
emit tileSetsChanged(); emit tileSetsChanged();
} }
QGCFetchTileSetTask* task = new QGCFetchTileSetTask(); QGCFetchTileSetTask* task = new QGCFetchTileSetTask();
@ -144,18 +144,6 @@ QGCMapEngineManager::_tileSetFetched(QGCCachedTileSet* tileSet)
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
QGCMapEngineManager::_clearTileSets()
{
while(_tileSets.count()) {
QGCCachedTileSet* tileSet = qobject_cast<QGCCachedTileSet*>(_tileSets[0]);
if(tileSet)
delete tileSet;
_tileSets.removeAt(0);
}
}
//-----------------------------------------------------------------------------
void
QGCMapEngineManager::startDownload(const QString& name, const QString& description, const QString& mapType, const QImage& image) QGCMapEngineManager::startDownload(const QString& name, const QString& description, const QString& mapType, const QImage& image)
{ {
if(_totalSet.tileSize) { if(_totalSet.tileSize) {

1
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h

@ -123,7 +123,6 @@ private slots:
void _resetCompleted (); void _resetCompleted ();
private: private:
void _clearTileSets ();
void _updateDiskFreeSpace (); void _updateDiskFreeSpace ();
private: private:

Loading…
Cancel
Save