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() @@ -114,7 +114,7 @@ destroyMapEngine()
//-----------------------------------------------------------------------------
QGCMapEngine::QGCMapEngine()
: _urlFactory(new UrlFactory::UrlFactory())
: _urlFactory(new UrlFactory())
#ifdef WE_ARE_KOSHER
//-- TODO: Get proper version
#if defined Q_OS_MAC
@ -173,6 +173,7 @@ QGCMapEngine::init() @@ -173,6 +173,7 @@ QGCMapEngine::init()
if(!_cachePath.isEmpty()) {
_cacheFile = kDbFileName;
_worker.setDatabaseFile(_cachePath + "/" + _cacheFile);
qDebug() << "Map Cache in:" << _cachePath << "/" << _cacheFile;
} else {
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 @@ -42,9 +42,8 @@ This file is part of the QGROUNDCONTROL project
class QGCCachedTileSet;
//-----------------------------------------------------------------------------
class QGCTile : public QObject
class QGCTile
{
Q_OBJECT
public:
QGCTile()
: _x(0)
@ -55,16 +54,6 @@ public: @@ -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 {
StatePending = 0,
StateDownloading,

8
src/QtLocationPlugin/QGCMapTileSet.cpp

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

4
src/QtLocationPlugin/QGCTileCacheWorker.cpp

@ -352,9 +352,8 @@ QGCCacheWorker::_getTileSets(QGCMapTask* mtask) @@ -352,9 +352,8 @@ QGCCacheWorker::_getTileSets(QGCMapTask* mtask)
void
QGCCacheWorker::_updateSetTotals(QGCCachedTileSet* set)
{
_updateTotals();
if(set->defaultSet()) {
//-- Default Set is already computed
_updateTotals();
set->setSavedTiles(_totalCount);
set->setSavedSize(_totalSize);
set->setNumTiles(_defaultCount);
@ -362,7 +361,6 @@ QGCCacheWorker::_updateSetTotals(QGCCachedTileSet* set) @@ -362,7 +361,6 @@ QGCCacheWorker::_updateSetTotals(QGCCachedTileSet* set)
return;
}
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());
if(subquery.exec(sq)) {
if(subquery.next()) {

4
src/QtLocationPlugin/QGeoTiledMappingManagerEngineQGC.cpp

@ -226,7 +226,9 @@ QGeoTiledMappingManagerEngineQGC::_setCache(const QVariantMap &parameters) @@ -226,7 +226,9 @@ QGeoTiledMappingManagerEngineQGC::_setCache(const QVariantMap &parameters)
QGeoTileCache* pTileCache = createTileCacheWithDir(cacheDir);
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);
}
}

63
src/QtLocationPlugin/QMLControl/OfflineMap.qml

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

16
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc

@ -54,7 +54,7 @@ QGCMapEngineManager::QGCMapEngineManager(QGCApplication* app) @@ -54,7 +54,7 @@ QGCMapEngineManager::QGCMapEngineManager(QGCApplication* app)
//-----------------------------------------------------------------------------
QGCMapEngineManager::~QGCMapEngineManager()
{
//_clearTileSets();
_tileSets.clear();
}
//-----------------------------------------------------------------------------
@ -120,7 +120,7 @@ void @@ -120,7 +120,7 @@ void
QGCMapEngineManager::loadTileSets()
{
if(_tileSets.count()) {
_clearTileSets();
_tileSets.clear();
emit tileSetsChanged();
}
QGCFetchTileSetTask* task = new QGCFetchTileSetTask();
@ -144,18 +144,6 @@ QGCMapEngineManager::_tileSetFetched(QGCCachedTileSet* tileSet) @@ -144,18 +144,6 @@ QGCMapEngineManager::_tileSetFetched(QGCCachedTileSet* tileSet)
//-----------------------------------------------------------------------------
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)
{
if(_totalSet.tileSize) {

1
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h

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

Loading…
Cancel
Save