1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-02-21 11:54:15 +01:00

OP-37 GCS/MapPlugin Widget user interaction started. Panning done (default right mouse button), MouseWheel Zooming done.

Fixed minor bug in get tiles threadpool 
Divided project in 3 different namespaces, introduced license info.
Current test project is "widgettest"

git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@699 ebee16cc-31ac-478f-84a7-5cbb03baadba
This commit is contained in:
zedamota 2010-06-01 22:08:57 +00:00 committed by zedamota
parent 754544f82b
commit 1f8bee643d
71 changed files with 2448 additions and 67 deletions

View File

@ -1,6 +1,35 @@
/**
******************************************************************************
*
* @file accessmode.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef ACCESSMODE_H #ifndef ACCESSMODE_H
#define ACCESSMODE_H #define ACCESSMODE_H
namespace core {
struct AccessMode struct AccessMode
{ {
@ -24,4 +53,5 @@ public:
}; };
}; };
}
#endif // ACCESSMODE_H #endif // ACCESSMODE_H

View File

@ -1,7 +1,36 @@
/**
******************************************************************************
*
* @file alllayersoftype.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "alllayersoftype.h" #include "alllayersoftype.h"
namespace core {
AllLayersOfType::AllLayersOfType() AllLayersOfType::AllLayersOfType()
{ {
@ -59,3 +88,4 @@ QVector<MapType::Types> AllLayersOfType::GetAllLayersOfType(const MapType::Types
return types; return types;
} }
}

View File

@ -1,9 +1,38 @@
/**
******************************************************************************
*
* @file alllayersoftype.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef ALLLAYERSOFTYPE_H #ifndef ALLLAYERSOFTYPE_H
#define ALLLAYERSOFTYPE_H #define ALLLAYERSOFTYPE_H
#include "maptype.h" #include "maptype.h"
#include <QList> #include <QList>
#include <QVector> #include <QVector>
namespace core {
class AllLayersOfType class AllLayersOfType
{ {
public: public:
@ -11,4 +40,5 @@ public:
QVector<MapType::Types> GetAllLayersOfType(const MapType::Types &type); QVector<MapType::Types> GetAllLayersOfType(const MapType::Types &type);
}; };
}
#endif // ALLLAYERSOFTYPE_H #endif // ALLLAYERSOFTYPE_H

View File

@ -1,5 +1,34 @@
/**
******************************************************************************
*
* @file cache.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "cache.h" #include "cache.h"
namespace core {
Cache* Cache::m_pInstance=0; Cache* Cache::m_pInstance=0;
Cache* Cache::Instance() Cache* Cache::Instance()
@ -62,24 +91,36 @@ void Cache::CacheGeocoder(const QString &urlEnd, const QString &content)
{ {
QString ret=QString::null; QString ret=QString::null;
QString filename=geoCache+QString(urlEnd)+".geo"; QString filename=geoCache+QString(urlEnd)+".geo";
#ifdef DEBUG_CACHE
qDebug()<<"CacheGeocoder: Filename:"<<filename; qDebug()<<"CacheGeocoder: Filename:"<<filename;
#endif //DEBUG_CACHE
QFileInfo File(filename);; QFileInfo File(filename);;
QDir dir=File.absoluteDir(); QDir dir=File.absoluteDir();
QString path=dir.absolutePath(); QString path=dir.absolutePath();
#ifdef DEBUG_CACHE
qDebug()<<"CacheGeocoder: Path:"<<path; qDebug()<<"CacheGeocoder: Path:"<<path;
#endif //DEBUG_CACHE
if(!dir.exists()) if(!dir.exists())
{ {
#ifdef DEBUG_CACHE
qDebug()<<"CacheGeocoder: Cache path doesn't exist, try to create"; qDebug()<<"CacheGeocoder: Cache path doesn't exist, try to create";
#endif //DEBUG_CACHE
if(!dir.mkpath(path)) if(!dir.mkpath(path))
{ {
#ifdef DEBUG_CACHE
qDebug()<<"GetGeocoderFromCache: Could not create path"; qDebug()<<"GetGeocoderFromCache: Could not create path";
#endif //DEBUG_CACHE
} }
} }
#ifdef DEBUG_CACHE
qDebug()<<"CacheGeocoder: OpenFile:"<<filename; qDebug()<<"CacheGeocoder: OpenFile:"<<filename;
#endif //DEBUG_CACHE
QFile file(filename); QFile file(filename);
if (file.open(QIODevice::WriteOnly)) if (file.open(QIODevice::WriteOnly))
{ {
#ifdef DEBUG_CACHE
qDebug()<<"CacheGeocoder: File Opened!!!:"<<filename; qDebug()<<"CacheGeocoder: File Opened!!!:"<<filename;
#endif //DEBUG_CACHE
QTextStream stream(&file); QTextStream stream(&file);
stream.setCodec("UTF-8"); stream.setCodec("UTF-8");
stream<<content; stream<<content;
@ -87,14 +128,20 @@ void Cache::CacheGeocoder(const QString &urlEnd, const QString &content)
} }
QString Cache::GetPlacemarkFromCache(const QString &urlEnd) QString Cache::GetPlacemarkFromCache(const QString &urlEnd)
{ {
#ifdef DEBUG_CACHE
qDebug()<<"Entered GetPlacemarkFromCache"; qDebug()<<"Entered GetPlacemarkFromCache";
#endif //DEBUG_CACHE
QString ret=QString::null; QString ret=QString::null;
QString filename=placemarkCache+QString(urlEnd)+".plc"; QString filename=placemarkCache+QString(urlEnd)+".plc";
#ifdef DEBUG_CACHE
qDebug()<<"GetPlacemarkFromCache: Does file exist?:"<<filename; qDebug()<<"GetPlacemarkFromCache: Does file exist?:"<<filename;
#endif //DEBUG_CACHE
QFileInfo File(filename); QFileInfo File(filename);
if (File .exists()) if (File .exists())
{ {
#ifdef DEBUG_CACHE
qDebug()<<"GetPlacemarkFromCache:File exists!!"; qDebug()<<"GetPlacemarkFromCache:File exists!!";
#endif //DEBUG_CACHE
QFile file(filename); QFile file(filename);
if (file.open(QIODevice::ReadOnly)) if (file.open(QIODevice::ReadOnly))
{ {
@ -103,33 +150,48 @@ QString Cache::GetPlacemarkFromCache(const QString &urlEnd)
stream>>ret; stream>>ret;
} }
} }
#ifdef DEBUG_CACHE
qDebug()<<"GetPlacemarkFromCache:Returning:"<<ret; qDebug()<<"GetPlacemarkFromCache:Returning:"<<ret;
#endif //DEBUG_CACHE
return ret; return ret;
} }
void Cache::CachePlacemark(const QString &urlEnd, const QString &content) void Cache::CachePlacemark(const QString &urlEnd, const QString &content)
{ {
QString ret=QString::null; QString ret=QString::null;
QString filename=placemarkCache+QString(urlEnd)+".plc"; QString filename=placemarkCache+QString(urlEnd)+".plc";
#ifdef DEBUG_CACHE
qDebug()<<"CachePlacemark: Filename:"<<filename; qDebug()<<"CachePlacemark: Filename:"<<filename;
#endif //DEBUG_CACHE
QFileInfo File(filename);; QFileInfo File(filename);;
QDir dir=File.absoluteDir(); QDir dir=File.absoluteDir();
QString path=dir.absolutePath(); QString path=dir.absolutePath();
#ifdef DEBUG_CACHE
qDebug()<<"CachePlacemark: Path:"<<path; qDebug()<<"CachePlacemark: Path:"<<path;
#endif //DEBUG_CACHE
if(!dir.exists()) if(!dir.exists())
{ {
#ifdef DEBUG_CACHE
qDebug()<<"CachePlacemark: Cache path doesn't exist, try to create"; qDebug()<<"CachePlacemark: Cache path doesn't exist, try to create";
#endif //DEBUG_CACHE
if(!dir.mkpath(path)) if(!dir.mkpath(path))
{ {
#ifdef DEBUG_CACHE
qDebug()<<"CachePlacemark: Could not create path"; qDebug()<<"CachePlacemark: Could not create path";
#endif //DEBUG_CACHE
} }
} }
#ifdef DEBUG_CACHE
qDebug()<<"CachePlacemark: OpenFile:"<<filename; qDebug()<<"CachePlacemark: OpenFile:"<<filename;
#endif //DEBUG_CACHE
QFile file(filename); QFile file(filename);
if (file.open(QIODevice::WriteOnly)) if (file.open(QIODevice::WriteOnly))
{ {
#ifdef DEBUG_CACHE
qDebug()<<"CachePlacemark: File Opened!!!:"<<filename; qDebug()<<"CachePlacemark: File Opened!!!:"<<filename;
#endif //DEBUG_CACHE
QTextStream stream(&file); QTextStream stream(&file);
stream.setCodec("UTF-8"); stream.setCodec("UTF-8");
stream<<content; stream<<content;
} }
} }
}

View File

@ -1,8 +1,37 @@
/**
******************************************************************************
*
* @file cache.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef CACHE_H #ifndef CACHE_H
#define CACHE_H #define CACHE_H
#include "pureimagecache.h" #include "pureimagecache.h"
namespace core {
class Cache class Cache
{ {
public: public:
@ -30,4 +59,5 @@ private:
QString placemarkCache; QString placemarkCache;
}; };
}
#endif // CACHE_H #endif // CACHE_H

View File

@ -1,5 +1,34 @@
/**
******************************************************************************
*
* @file cacheitemqueue.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "cacheitemqueue.h" #include "cacheitemqueue.h"
namespace core {
CacheItemQueue::CacheItemQueue(const MapType::Types &Type, const Point &Pos, const QByteArray &Img, const int &Zoom) CacheItemQueue::CacheItemQueue(const MapType::Types &Type, const Point &Pos, const QByteArray &Img, const int &Zoom)
{ {
type=Type; type=Type;
@ -48,3 +77,4 @@ bool CacheItemQueue::operator ==(const CacheItemQueue &cSource)
bool b=(img==cSource.img)&& (pos==cSource.pos) && (type==cSource.type) && (zoom==cSource.zoom); bool b=(img==cSource.img)&& (pos==cSource.pos) && (type==cSource.type) && (zoom==cSource.zoom);
return b; return b;
} }
}

View File

@ -1,3 +1,30 @@
/**
******************************************************************************
*
* @file cacheitemqueue.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef CACHEITEMQUEUE_H #ifndef CACHEITEMQUEUE_H
#define CACHEITEMQUEUE_H #define CACHEITEMQUEUE_H
@ -6,6 +33,8 @@
#include <QByteArray> #include <QByteArray>
namespace core {
class CacheItemQueue class CacheItemQueue
{ {
public: public:
@ -37,4 +66,5 @@ private:
int zoom; int zoom;
}; };
}
#endif // CACHEITEMQUEUE_H #endif // CACHEITEMQUEUE_H

View File

@ -1,6 +1,35 @@
/**
******************************************************************************
*
* @file geodecoderstatus.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef GEODECODERSTATUS_H #ifndef GEODECODERSTATUS_H
#define GEODECODERSTATUS_H #define GEODECODERSTATUS_H
namespace core {
struct GeoCoderStatusCode struct GeoCoderStatusCode
{ {
enum Types enum Types
@ -68,4 +97,5 @@ struct GeoCoderStatusCode
}; };
}; };
}
#endif // GEODECODERSTATUS_H #endif // GEODECODERSTATUS_H

View File

@ -1,14 +1,43 @@
/**
******************************************************************************
*
* @file OPMaps.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "gmaps.h" #include "gmaps.h"
GMaps* GMaps::m_pInstance=0;
GMaps* GMaps::Instance() namespace core {
OPMaps* OPMaps::m_pInstance=0;
OPMaps* OPMaps::Instance()
{ {
if(!m_pInstance) if(!m_pInstance)
m_pInstance=new GMaps; m_pInstance=new OPMaps;
return m_pInstance; return m_pInstance;
} }
GMaps::GMaps():useMemoryCache(true),MaxZoom(19),RetryLoadTile(2) OPMaps::OPMaps():useMemoryCache(true),MaxZoom(19),RetryLoadTile(2)
{ {
accessmode=AccessMode::ServerAndCache; accessmode=AccessMode::ServerAndCache;
Language=LanguageType::PortuguesePortugal; Language=LanguageType::PortuguesePortugal;
@ -18,37 +47,49 @@ GMaps::GMaps():useMemoryCache(true),MaxZoom(19),RetryLoadTile(2)
} }
GMaps::~GMaps() OPMaps::~OPMaps()
{ {
//delete Proxy; //delete Proxy;
} }
QByteArray GMaps::GetImageFrom(const MapType::Types &type,const Point &pos,const int &zoom) QByteArray OPMaps::GetImageFrom(const MapType::Types &type,const Point &pos,const int &zoom)
{ {
#ifdef DEBUG_GMAPS
qDebug()<<"Entered GetImageFrom"; qDebug()<<"Entered GetImageFrom";
#endif //DEBUG_GMAPS
QByteArray ret; QByteArray ret;
if(useMemoryCache) if(useMemoryCache)
{ {
#ifdef DEBUG_GMAPS
qDebug()<<"Try Tile from memory:Size="<<TilesInMemory.MemoryCacheSize(); qDebug()<<"Try Tile from memory:Size="<<TilesInMemory.MemoryCacheSize();
#endif //DEBUG_GMAPS
ret=GetTileFromMemoryCache(RawTile(type,pos,zoom)); ret=GetTileFromMemoryCache(RawTile(type,pos,zoom));
} }
if(ret.isEmpty()) if(ret.isEmpty())
{ {
#ifdef DEBUG_GMAPS
qDebug()<<"Tile not in memory"; qDebug()<<"Tile not in memory";
#endif //DEBUG_GMAPS
if(accessmode != (AccessMode::ServerOnly)) if(accessmode != (AccessMode::ServerOnly))
{ {
#ifdef DEBUG_GMAPS
qDebug()<<"Try tile from DataBase"; qDebug()<<"Try tile from DataBase";
#endif //DEBUG_GMAPS
ret=Cache::Instance()->ImageCache.GetImageFromCache(type,pos,zoom); ret=Cache::Instance()->ImageCache.GetImageFromCache(type,pos,zoom);
if(!ret.isEmpty()) if(!ret.isEmpty())
{ {
#ifdef DEBUG_GMAPS
qDebug()<<"Tile found in Database"; qDebug()<<"Tile found in Database";
#endif //DEBUG_GMAPS
if(useMemoryCache) if(useMemoryCache)
{ {
#ifdef DEBUG_GMAPS
qDebug()<<"Add Tile to memory"; qDebug()<<"Add Tile to memory";
#endif //DEBUG_GMAPS
AddTileToMemoryCache(RawTile(type,pos,zoom),ret); AddTileToMemoryCache(RawTile(type,pos,zoom),ret);
} }
return ret; return ret;
@ -60,7 +101,9 @@ QByteArray GMaps::GetImageFrom(const MapType::Types &type,const Point &pos,const
QNetworkRequest qheader; QNetworkRequest qheader;
QNetworkAccessManager network; QNetworkAccessManager network;
network.setProxy(Proxy); network.setProxy(Proxy);
#ifdef DEBUG_GMAPS
qDebug()<<"Try Tile from the Internet"; qDebug()<<"Try Tile from the Internet";
#endif //DEBUG_GMAPS
QString url=MakeImageUrl(type,pos,zoom,LanguageStr); QString url=MakeImageUrl(type,pos,zoom,LanguageStr);
qheader.setUrl(QUrl(url)); qheader.setUrl(QUrl(url));
qheader.setRawHeader("User-Agent",UserAgent); qheader.setRawHeader("User-Agent",UserAgent);
@ -136,33 +179,49 @@ QByteArray GMaps::GetImageFrom(const MapType::Types &type,const Point &pos,const
break; break;
} }
reply=network.get(qheader); reply=network.get(qheader);
#ifdef DEBUG_GMAPS
qDebug()<<"Starting get response ";//<<pos.X()+","+pos.Y(); qDebug()<<"Starting get response ";//<<pos.X()+","+pos.Y();
#endif //DEBUG_GMAPS
QTime time; QTime time;
time.start(); time.start();
while( !(reply->isFinished() | time.elapsed()>(6*Timeout)) ){QCoreApplication::processEvents(QEventLoop::AllEvents);} while( !(reply->isFinished() | time.elapsed()>(6*Timeout)) ){QCoreApplication::processEvents(QEventLoop::AllEvents);}
#ifdef DEBUG_GMAPS
qDebug()<<"Finished?"<<reply->error()<<" abort?"<<(time.elapsed()>Timeout*6); qDebug()<<"Finished?"<<reply->error()<<" abort?"<<(time.elapsed()>Timeout*6);
#endif //DEBUG_GMAPS
if( (reply->error()!=QNetworkReply::NoError) | (time.elapsed()>Timeout*6)) if( (reply->error()!=QNetworkReply::NoError) | (time.elapsed()>Timeout*6))
{ {
#ifdef DEBUG_GMAPS
qDebug()<<"Request timed out ";//<<pos.x+","+pos.y; qDebug()<<"Request timed out ";//<<pos.x+","+pos.y;
#endif //DEBUG_GMAPS
return ret; return ret;
} }
#ifdef DEBUG_GMAPS
qDebug()<<"Response OK ";//<<pos.x+","+pos.y; qDebug()<<"Response OK ";//<<pos.x+","+pos.y;
#endif //DEBUG_GMAPS
ret=reply->readAll(); ret=reply->readAll();
reply->deleteLater();//TODO can't this be global?? reply->deleteLater();//TODO can't this be global??
if(ret.isEmpty()) if(ret.isEmpty())
{ {
#ifdef DEBUG_GMAPS
qDebug()<<"Invalid Tile"; qDebug()<<"Invalid Tile";
#endif //DEBUG_GMAPS
return ret; return ret;
} }
#ifdef DEBUG_GMAPS
qDebug()<<"Received Tile from the Internet"; qDebug()<<"Received Tile from the Internet";
#endif //DEBUG_GMAPS
if (useMemoryCache) if (useMemoryCache)
{ {
#ifdef DEBUG_GMAPS
qDebug()<<"Add Tile to memory cache"; qDebug()<<"Add Tile to memory cache";
#endif //DEBUG_GMAPS
AddTileToMemoryCache(RawTile(type,pos,zoom),ret); AddTileToMemoryCache(RawTile(type,pos,zoom),ret);
} }
if(accessmode!=AccessMode::ServerOnly) if(accessmode!=AccessMode::ServerOnly)
{ {
#ifdef DEBUG_GMAPS
qDebug()<<"Add tile to DataBase"; qDebug()<<"Add tile to DataBase";
#endif //DEBUG_GMAPS
CacheItemQueue item(type,pos,ret,zoom); CacheItemQueue item(type,pos,ret,zoom);
TileDBcacheQueue.EnqueueCacheTask(item); TileDBcacheQueue.EnqueueCacheTask(item);
} }
@ -170,15 +229,18 @@ QByteArray GMaps::GetImageFrom(const MapType::Types &type,const Point &pos,const
} }
} }
#ifdef DEBUG_GMAPS
qDebug()<<"Entered GetImageFrom"; qDebug()<<"Entered GetImageFrom";
#endif //DEBUG_GMAPS
return ret; return ret;
} }
bool GMaps::ExportToGMDB(const QString &file) bool OPMaps::ExportToGMDB(const QString &file)
{ {
return Cache::Instance()->ImageCache.ExportMapDataToDB(Cache::Instance()->ImageCache.GtileCache()+QDir::separator()+"Data.qmdb",file); return Cache::Instance()->ImageCache.ExportMapDataToDB(Cache::Instance()->ImageCache.GtileCache()+QDir::separator()+"Data.qmdb",file);
} }
bool GMaps::ImportFromGMDB(const QString &file) bool OPMaps::ImportFromGMDB(const QString &file)
{ {
return Cache::Instance()->ImageCache.ExportMapDataToDB(file,Cache::Instance()->ImageCache.GtileCache()+QDir::separator()+"Data.qmdb"); return Cache::Instance()->ImageCache.ExportMapDataToDB(file,Cache::Instance()->ImageCache.GtileCache()+QDir::separator()+"Data.qmdb");
} }
}

View File

@ -1,5 +1,38 @@
#ifndef GMAPS_H /**
#define GMAPS_H ******************************************************************************
*
* @file OPMaps.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef OPMaps_H
#define OPMaps_H
//#define DEBUG_CACHE
//#define DEBUG_GMAPS
//#define DEBUG_PUREIMAGECACHE
//#define DEBUG_TILECACHEQUEUE
//#define DEBUG_URLFACTORY
#include "memorycache.h" #include "memorycache.h"
#include "rawtile.h" #include "rawtile.h"
@ -13,15 +46,17 @@
#include "urlfactory.h" #include "urlfactory.h"
//#include "point.h" //#include "point.h"
class GMaps: public MemoryCache,public AllLayersOfType,public UrlFactory
namespace core {
class OPMaps: public MemoryCache,public AllLayersOfType,public UrlFactory
{ {
public: public:
~GMaps(); ~OPMaps();
static GMaps* Instance(); static OPMaps* Instance();
bool ImportFromGMDB(const QString &file); bool ImportFromGMDB(const QString &file);
bool ExportToGMDB(const QString &file); bool ExportToGMDB(const QString &file);
/// <summary> /// <summary>
@ -49,11 +84,11 @@ private:
// PureImageCache ImageCacheLocal;//TODO Criar acesso Get Set // PureImageCache ImageCacheLocal;//TODO Criar acesso Get Set
TileCacheQueue TileDBcacheQueue; TileCacheQueue TileDBcacheQueue;
GMaps(); OPMaps();
GMaps(GMaps const&){}; OPMaps(OPMaps const&){};
GMaps& operator=(GMaps const&){}; OPMaps& operator=(OPMaps const&){};
static GMaps* m_pInstance; static OPMaps* m_pInstance;
protected: protected:
@ -63,4 +98,5 @@ protected:
}; };
#endif // GMAPS_H }
#endif // OPMaps_H

View File

@ -1,6 +1,35 @@
/**
******************************************************************************
*
* @file kibertilecache.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "kibertilecache.h" #include "kibertilecache.h"
//TODO add readwrite lock //TODO add readwrite lock
namespace core {
KiberTileCache::KiberTileCache() KiberTileCache::KiberTileCache()
{ {
memoryCacheSize = 0; memoryCacheSize = 0;
@ -32,3 +61,4 @@ void KiberTileCache::RemoveMemoryOverload()
} }
} }
} }
}

View File

@ -1,3 +1,30 @@
/**
******************************************************************************
*
* @file kibertilecache.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef KIBERTILECACHE_H #ifndef KIBERTILECACHE_H
#define KIBERTILECACHE_H #define KIBERTILECACHE_H
@ -7,6 +34,8 @@
#include <QReadWriteLock> #include <QReadWriteLock>
#include <QQueue> #include <QQueue>
namespace core {
class KiberTileCache class KiberTileCache
{ {
public: public:
@ -30,4 +59,5 @@ private:
}
#endif // KIBERTILECACHE_H #endif // KIBERTILECACHE_H

View File

@ -1,6 +1,35 @@
/**
******************************************************************************
*
* @file languagetype.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "languagetype.h" #include "languagetype.h"
namespace core {
LanguageType::LanguageType() LanguageType::LanguageType()
{ {
list list
@ -69,3 +98,4 @@ LanguageType::~LanguageType()
list.clear(); list.clear();
} }
}

View File

@ -1,3 +1,30 @@
/**
******************************************************************************
*
* @file languagetype.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef LANGUAGETYPE_H #ifndef LANGUAGETYPE_H
#define LANGUAGETYPE_H #define LANGUAGETYPE_H
@ -5,6 +32,8 @@
#include <QStringList> #include <QStringList>
namespace core {
class LanguageType class LanguageType
{ {
public: public:
@ -75,4 +104,5 @@ private:
QStringList list; QStringList list;
}; };
}
#endif // LANGUAGETYPE_H #endif // LANGUAGETYPE_H

View File

@ -1,6 +1,35 @@
/**
******************************************************************************
*
* @file maptype.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef MAPTYPE_H #ifndef MAPTYPE_H
#define MAPTYPE_H #define MAPTYPE_H
namespace core {
struct MapType struct MapType
{ {
enum Types enum Types
@ -66,4 +95,5 @@ struct MapType
YandexMapRu = 5000, YandexMapRu = 5000,
}; };
}; };
}
#endif // MAPTYPE_H #endif // MAPTYPE_H

View File

@ -1,5 +1,34 @@
/**
******************************************************************************
*
* @file memorycache.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "memorycache.h" #include "memorycache.h"
//TODO add readwrite lock //TODO add readwrite lock
namespace core {
MemoryCache::MemoryCache() MemoryCache::MemoryCache()
{ {
@ -26,3 +55,4 @@ void MemoryCache::AddTileToMemoryCache(const RawTile &tile, const QByteArray &pi
kiberCacheLock.unlock(); kiberCacheLock.unlock();
} }
}

View File

@ -1,3 +1,30 @@
/**
******************************************************************************
*
* @file memorycache.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef MEMORYCACHE_H #ifndef MEMORYCACHE_H
#define MEMORYCACHE_H #define MEMORYCACHE_H
@ -7,6 +34,8 @@
#include <QReadWriteLock> #include <QReadWriteLock>
#include <QQueue> #include <QQueue>
#include "kibertilecache.h" #include "kibertilecache.h"
namespace core {
class MemoryCache class MemoryCache
{ {
public: public:
@ -20,4 +49,5 @@ public:
}; };
}
#endif // MEMORYCACHE_H #endif // MEMORYCACHE_H

View File

@ -1,2 +1,29 @@
/**
******************************************************************************
*
* @file placemark.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "placemark.h" #include "placemark.h"

View File

@ -1,8 +1,37 @@
/**
******************************************************************************
*
* @file placemark.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PLACEMARK_H #ifndef PLACEMARK_H
#define PLACEMARK_H #define PLACEMARK_H
#include <QString> #include <QString>
namespace core {
class Placemark class Placemark
{ {
public: public:
@ -22,4 +51,5 @@ protected:
}; };
}
#endif // PLACEMARK_H #endif // PLACEMARK_H

View File

@ -1,5 +1,34 @@
/**
******************************************************************************
*
* @file point.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "point.h" #include "point.h"
#include "size.h" #include "size.h"
namespace core {
Point::Point(int dw) Point::Point(int dw)
{ {
this->x=(short)Point::LOWORD(dw); this->x=(short)Point::LOWORD(dw);
@ -43,3 +72,4 @@ int Point::LOWORD(int n)
} }
Point Point::Empty=Point(); Point Point::Empty=Point();
}

View File

@ -1,9 +1,38 @@
/**
******************************************************************************
*
* @file point.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef POINT_H #ifndef POINT_H
#define POINT_H #define POINT_H
#include <QString> #include <QString>
//#include "size.h" //#include "size.h"
namespace core {
struct Size; struct Size;
struct Point struct Point
{ {
@ -44,4 +73,5 @@ private:
}
#endif // POINT_H #endif // POINT_H

View File

@ -1,5 +1,34 @@
/**
******************************************************************************
*
* @file providerstrings.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "providerstrings.h" #include "providerstrings.h"
namespace core {
const QString ProviderStrings::levelsForSigPacSpainMap[] = {"0", "1", "2", "3", "4", const QString ProviderStrings::levelsForSigPacSpainMap[] = {"0", "1", "2", "3", "4",
"MTNSIGPAC", "MTNSIGPAC",
"MTN2000", "MTN2000", "MTN2000", "MTN2000", "MTN2000", "MTN2000", "MTN2000", "MTN2000", "MTN2000", "MTN2000",
@ -51,3 +80,4 @@ ProviderStrings::ProviderStrings()
BingMapsClientToken = ""; BingMapsClientToken = "";
} }
}

View File

@ -1,8 +1,37 @@
/**
******************************************************************************
*
* @file providerstrings.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PROVIDERSTRINGS_H #ifndef PROVIDERSTRINGS_H
#define PROVIDERSTRINGS_H #define PROVIDERSTRINGS_H
#include <QString> #include <QString>
namespace core {
class ProviderStrings class ProviderStrings
{ {
public: public:
@ -53,4 +82,5 @@ public:
QString BingMapsClientToken; QString BingMapsClientToken;
}; };
}
#endif // PROVIDERSTRINGS_H #endif // PROVIDERSTRINGS_H

View File

@ -1,6 +1,35 @@
/**
******************************************************************************
*
* @file pureimage.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "pureimage.h" #include "pureimage.h"
namespace core {
PureImageProxy::PureImageProxy() PureImageProxy::PureImageProxy()
{ {
@ -15,3 +44,4 @@ bool PureImageProxy::Save(const QByteArray &array, QPixmap &pic)
pic=QPixmap::fromImage(QImage::fromData(array)); pic=QPixmap::fromImage(QImage::fromData(array));
return true; return true;
} }
}

View File

@ -1,9 +1,38 @@
/**
******************************************************************************
*
* @file pureimage.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PUREIMAGE_H #ifndef PUREIMAGE_H
#define PUREIMAGE_H #define PUREIMAGE_H
#include <QPixmap> #include <QPixmap>
#include <QByteArray> #include <QByteArray>
namespace core {
class PureImageProxy class PureImageProxy
{ {
public: public:
@ -12,4 +41,5 @@ public:
static bool Save(const QByteArray &array,QPixmap &pic); static bool Save(const QByteArray &array,QPixmap &pic);
}; };
}
#endif // PUREIMAGE_H #endif // PUREIMAGE_H

View File

@ -1,5 +1,34 @@
/**
******************************************************************************
*
* @file pureimagecache.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "pureimagecache.h" #include "pureimagecache.h"
namespace core {
qlonglong PureImageCache::ConnCounter=0; qlonglong PureImageCache::ConnCounter=0;
PureImageCache::PureImageCache() PureImageCache::PureImageCache()
@ -20,7 +49,9 @@ QString PureImageCache::GtileCache()
bool PureImageCache::CreateEmptyDB(const QString &file) bool PureImageCache::CreateEmptyDB(const QString &file)
{ {
#ifdef DEBUG_PUREIMAGECACHE
qDebug()<<"Create database at:"<<file; qDebug()<<"Create database at:"<<file;
#endif //DEBUG_PUREIMAGECACHE
QFileInfo File(file); QFileInfo File(file);
QDir dir=File.absoluteDir(); QDir dir=File.absoluteDir();
QString path=dir.absolutePath(); QString path=dir.absolutePath();
@ -28,10 +59,14 @@ bool PureImageCache::CreateEmptyDB(const QString &file)
if(File.exists()) QFile(filename).remove(); if(File.exists()) QFile(filename).remove();
if(!dir.exists()) if(!dir.exists())
{ {
#ifdef DEBUG_PUREIMAGECACHE
qDebug()<<"CreateEmptyDB: Cache path doesn't exist, try to create"; qDebug()<<"CreateEmptyDB: Cache path doesn't exist, try to create";
#endif //DEBUG_PUREIMAGECACHE
if(!dir.mkpath(path)) if(!dir.mkpath(path))
{ {
#ifdef DEBUG_PUREIMAGECACHE
qDebug()<<"CreateEmptyDB: Could not create path"; qDebug()<<"CreateEmptyDB: Could not create path";
#endif //DEBUG_PUREIMAGECACHE
return false; return false;
} }
} }
@ -41,7 +76,9 @@ bool PureImageCache::CreateEmptyDB(const QString &file)
db.setDatabaseName(file); db.setDatabaseName(file);
if (!db.open()) if (!db.open())
{ {
#ifdef DEBUG_PUREIMAGECACHE
qDebug()<<"CreateEmptyDB: Unable to create database"; qDebug()<<"CreateEmptyDB: Unable to create database";
#endif //DEBUG_PUREIMAGECACHE
return false; return false;
} }
@ -49,14 +86,18 @@ bool PureImageCache::CreateEmptyDB(const QString &file)
query.exec("CREATE TABLE IF NOT EXISTS Tiles (id INTEGER NOT NULL PRIMARY KEY, X INTEGER NOT NULL, Y INTEGER NOT NULL, Zoom INTEGER NOT NULL, Type INTEGER NOT NULL)"); query.exec("CREATE TABLE IF NOT EXISTS Tiles (id INTEGER NOT NULL PRIMARY KEY, X INTEGER NOT NULL, Y INTEGER NOT NULL, Zoom INTEGER NOT NULL, Type INTEGER NOT NULL)");
if(query.numRowsAffected()==-1) if(query.numRowsAffected()==-1)
{ {
#ifdef DEBUG_PUREIMAGECACHE
qDebug()<<"CreateEmptyDB: "<<query.lastError().driverText(); qDebug()<<"CreateEmptyDB: "<<query.lastError().driverText();
#endif //DEBUG_PUREIMAGECACHE
db.close(); db.close();
return false; return false;
} }
query.exec("CREATE TABLE IF NOT EXISTS TilesData (id INTEGER NOT NULL PRIMARY KEY CONSTRAINT fk_Tiles_id REFERENCES Tiles(id) ON DELETE CASCADE, Tile BLOB NULL)"); query.exec("CREATE TABLE IF NOT EXISTS TilesData (id INTEGER NOT NULL PRIMARY KEY CONSTRAINT fk_Tiles_id REFERENCES Tiles(id) ON DELETE CASCADE, Tile BLOB NULL)");
if(query.numRowsAffected()==-1) if(query.numRowsAffected()==-1)
{ {
#ifdef DEBUG_PUREIMAGECACHE
qDebug()<<"CreateEmptyDB: "<<query.lastError().driverText(); qDebug()<<"CreateEmptyDB: "<<query.lastError().driverText();
#endif //DEBUG_PUREIMAGECACHE
db.close(); db.close();
return false; return false;
} }
@ -69,7 +110,9 @@ bool PureImageCache::CreateEmptyDB(const QString &file)
"END"); "END");
if(query.numRowsAffected()==-1) if(query.numRowsAffected()==-1)
{ {
#ifdef DEBUG_PUREIMAGECACHE
qDebug()<<"CreateEmptyDB: "<<query.lastError().driverText(); qDebug()<<"CreateEmptyDB: "<<query.lastError().driverText();
#endif //DEBUG_PUREIMAGECACHE
db.close(); db.close();
return false; return false;
} }
@ -82,7 +125,9 @@ bool PureImageCache::CreateEmptyDB(const QString &file)
"END"); "END");
if(query.numRowsAffected()==-1) if(query.numRowsAffected()==-1)
{ {
#ifdef DEBUG_PUREIMAGECACHE
qDebug()<<"CreateEmptyDB: "<<query.lastError().driverText(); qDebug()<<"CreateEmptyDB: "<<query.lastError().driverText();
#endif //DEBUG_PUREIMAGECACHE
db.close(); db.close();
return false; return false;
} }
@ -94,7 +139,9 @@ bool PureImageCache::CreateEmptyDB(const QString &file)
"END"); "END");
if(query.numRowsAffected()==-1) if(query.numRowsAffected()==-1)
{ {
#ifdef DEBUG_PUREIMAGECACHE
qDebug()<<"CreateEmptyDB: "<<query.lastError().driverText(); qDebug()<<"CreateEmptyDB: "<<query.lastError().driverText();
#endif //DEBUG_PUREIMAGECACHE
db.close(); db.close();
return false; return false;
} }
@ -103,22 +150,30 @@ bool PureImageCache::CreateEmptyDB(const QString &file)
} }
bool PureImageCache::PutImageToCache(const QByteArray &tile, const MapType::Types &type,const Point &pos,const int &zoom) bool PureImageCache::PutImageToCache(const QByteArray &tile, const MapType::Types &type,const Point &pos,const int &zoom)
{ {
#ifdef DEBUG_PUREIMAGECACHE
qDebug()<<"PutImageToCache Start:";//<<pos; qDebug()<<"PutImageToCache Start:";//<<pos;
#endif //DEBUG_PUREIMAGECACHE
bool ret=true; bool ret=true;
QDir d; QDir d;
QString dir=gtilecache; QString dir=gtilecache;
#ifdef DEBUG_PUREIMAGECACHE
qDebug()<<"PutImageToCache Cache dir="<<dir; qDebug()<<"PutImageToCache Cache dir="<<dir;
qDebug()<<"PutImageToCache Cache dir="<<dir<<" Try to PUT:"<<pos.ToString(); qDebug()<<"PutImageToCache Cache dir="<<dir<<" Try to PUT:"<<pos.ToString();
#endif //DEBUG_PUREIMAGECACHE
if(!d.exists(dir)) if(!d.exists(dir))
{ {
d.mkdir(dir); d.mkdir(dir);
#ifdef DEBUG_PUREIMAGECACHE
qDebug()<<"Create Cache directory"; qDebug()<<"Create Cache directory";
#endif //DEBUG_PUREIMAGECACHE
} }
{ {
QString db=dir+"Data.qmdb"; QString db=dir+"Data.qmdb";
if(!QFileInfo(db).exists()) if(!QFileInfo(db).exists())
{ {
#ifdef DEBUG_PUREIMAGECACHE
qDebug()<<"Try to create EmptyDB"; qDebug()<<"Try to create EmptyDB";
#endif //DEBUG_PUREIMAGECACHE
ret=CreateEmptyDB(db); ret=CreateEmptyDB(db);
} }
if(ret) if(ret)
@ -153,7 +208,9 @@ bool PureImageCache::PutImageToCache(const QByteArray &tile, const MapType::Type
} }
else else
{ {
#ifdef DEBUG_PUREIMAGECACHE
qDebug()<<"PutImageToCache Could not create DB"; qDebug()<<"PutImageToCache Could not create DB";
#endif //DEBUG_PUREIMAGECACHE
return false; return false;
} }
} }
@ -164,7 +221,9 @@ QByteArray PureImageCache::GetImageFromCache(MapType::Types type, Point pos, int
bool ret=true; bool ret=true;
QByteArray ar; QByteArray ar;
QString dir=gtilecache; QString dir=gtilecache;
#ifdef DEBUG_PUREIMAGECACHE
qDebug()<<"Cache dir="<<dir<<" Try to GET:"<<pos.X()+","+pos.Y(); qDebug()<<"Cache dir="<<dir<<" Try to GET:"<<pos.X()+","+pos.Y();
#endif //DEBUG_PUREIMAGECACHE
{ {
QString db=dir+"Data.qmdb"; QString db=dir+"Data.qmdb";
@ -199,7 +258,9 @@ bool PureImageCache::ExportMapDataToDB(QString sourceFile, QString destFile)
QList<long> add; QList<long> add;
if(!QFileInfo(destFile).exists()) if(!QFileInfo(destFile).exists())
{ {
#ifdef DEBUG_PUREIMAGECACHE
qDebug()<<"Try to create EmptyDB"; qDebug()<<"Try to create EmptyDB";
#endif //DEBUG_PUREIMAGECACHE
ret=CreateEmptyDB(destFile); ret=CreateEmptyDB(destFile);
} }
if(!ret) return false; if(!ret) return false;
@ -245,3 +306,4 @@ bool PureImageCache::ExportMapDataToDB(QString sourceFile, QString destFile)
} }
}

View File

@ -1,3 +1,30 @@
/**
******************************************************************************
*
* @file pureimagecache.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PUREIMAGECACHE_H #ifndef PUREIMAGECACHE_H
#define PUREIMAGECACHE_H #define PUREIMAGECACHE_H
@ -18,6 +45,8 @@
namespace core {
class PureImageCache class PureImageCache
{ {
@ -35,4 +64,5 @@ private:
static qlonglong ConnCounter; static qlonglong ConnCounter;
}; };
}
#endif // PUREIMAGECACHE_H #endif // PUREIMAGECACHE_H

View File

@ -1,5 +1,34 @@
/**
******************************************************************************
*
* @file rawtile.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "rawtile.h" #include "rawtile.h"
namespace core {
RawTile::RawTile(const MapType::Types &Type, const Point &Pos, const int &Zoom) RawTile::RawTile(const MapType::Types &Type, const Point &Pos, const int &Zoom)
{ {
zoom=Zoom; zoom=Zoom;
@ -45,3 +74,4 @@ bool operator==(RawTile const &lhs,RawTile const &rhs)
{ {
return (lhs.pos==rhs.pos && lhs.zoom==rhs.zoom && lhs.type==rhs.type); return (lhs.pos==rhs.pos && lhs.zoom==rhs.zoom && lhs.type==rhs.type);
} }
}

View File

@ -1,3 +1,30 @@
/**
******************************************************************************
*
* @file rawtile.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef RAWTILE_H #ifndef RAWTILE_H
#define RAWTILE_H #define RAWTILE_H
@ -5,6 +32,8 @@
#include "point.h" #include "point.h"
#include <QString> #include <QString>
#include <QHash> #include <QHash>
namespace core {
class RawTile class RawTile
{ {
friend uint qHash(RawTile const& tile); friend uint qHash(RawTile const& tile);
@ -27,4 +56,5 @@ private:
//uint qHash(RawTile const& tile); //uint qHash(RawTile const& tile);
//bool operator==(RawTile const& lhs,RawTile const& rhs); //bool operator==(RawTile const& lhs,RawTile const& rhs);
}
#endif // RAWTILE_H #endif // RAWTILE_H

View File

@ -1,4 +1,34 @@
/**
******************************************************************************
*
* @file size.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "size.h" #include "size.h"
namespace core {
Size::Size():width(0),height(0) Size::Size():width(0),height(0)
{} {}
}

View File

@ -1,9 +1,38 @@
/**
******************************************************************************
*
* @file size.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef SIZE_H #ifndef SIZE_H
#define SIZE_H #define SIZE_H
#include "point.h" #include "point.h"
#include <QString> #include <QString>
#include <QHash> #include <QHash>
namespace core {
struct Size struct Size
{ {
@ -29,4 +58,5 @@ private:
}; };
//bool operator==(Size const& lhs,Size const& rhs){return (lhs.width==rhs.width && lhs.height==rhs.height);} //bool operator==(Size const& lhs,Size const& rhs){return (lhs.width==rhs.width && lhs.height==rhs.height);}
}
#endif // SIZE_H #endif // SIZE_H

View File

@ -1,7 +1,36 @@
/**
******************************************************************************
*
* @file tilecachequeue.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "tilecachequeue.h" #include "tilecachequeue.h"
namespace core {
TileCacheQueue::TileCacheQueue() TileCacheQueue::TileCacheQueue()
{ {
@ -9,21 +38,29 @@ TileCacheQueue::TileCacheQueue()
void TileCacheQueue::EnqueueCacheTask(CacheItemQueue &task) void TileCacheQueue::EnqueueCacheTask(CacheItemQueue &task)
{ {
#ifdef DEBUG_TILECACHEQUEUE
qDebug()<<"DB Do I EnqueueCacheTask"<<task.GetPosition().X()<<","<<task.GetPosition().Y(); qDebug()<<"DB Do I EnqueueCacheTask"<<task.GetPosition().X()<<","<<task.GetPosition().Y();
#endif //DEBUG_TILECACHEQUEUE
if(!tileCacheQueue.contains(task)) if(!tileCacheQueue.contains(task))
{ {
#ifdef DEBUG_TILECACHEQUEUE
qDebug()<<"EnqueueCacheTask"<<task.GetPosition().X()<<","<<task.GetPosition().Y(); qDebug()<<"EnqueueCacheTask"<<task.GetPosition().X()<<","<<task.GetPosition().Y();
#endif //DEBUG_TILECACHEQUEUE
mutex.lock(); mutex.lock();
tileCacheQueue.enqueue(task); tileCacheQueue.enqueue(task);
mutex.unlock(); mutex.unlock();
if(this->isRunning()) if(this->isRunning())
{ {
#ifdef DEBUG_TILECACHEQUEUE
qDebug()<<"Wake Thread"; qDebug()<<"Wake Thread";
#endif //DEBUG_TILECACHEQUEUE
wait.wakeOne(); wait.wakeOne();
} }
else else
{ {
#ifdef DEBUG_TILECACHEQUEUE
qDebug()<<"Start Thread"; qDebug()<<"Start Thread";
#endif //DEBUG_TILECACHEQUEUE
this->start(QThread::LowestPriority); this->start(QThread::LowestPriority);
} }
} }
@ -31,17 +68,23 @@ void TileCacheQueue::EnqueueCacheTask(CacheItemQueue &task)
} }
void TileCacheQueue::run() void TileCacheQueue::run()
{ {
#ifdef DEBUG_TILECACHEQUEUE
qDebug()<<"Cache Engine Start"; qDebug()<<"Cache Engine Start";
#endif //DEBUG_TILECACHEQUEUE
while(true) while(true)
{ {
CacheItemQueue task; CacheItemQueue task;
#ifdef DEBUG_TILECACHEQUEUE
qDebug()<<"Cache"; qDebug()<<"Cache";
#endif //DEBUG_TILECACHEQUEUE
if(tileCacheQueue.count()>0) if(tileCacheQueue.count()>0)
{ {
mutex.lock(); mutex.lock();
task=tileCacheQueue.dequeue(); task=tileCacheQueue.dequeue();
mutex.unlock(); mutex.unlock();
#ifdef DEBUG_TILECACHEQUEUE
qDebug()<<"Cache engine Put:"<<task.GetPosition().X()<<","<<task.GetPosition().Y(); qDebug()<<"Cache engine Put:"<<task.GetPosition().X()<<","<<task.GetPosition().Y();
#endif //DEBUG_TILECACHEQUEUE
Cache::Instance()->ImageCache.PutImageToCache(task.GetImg(),task.GetMapType(),task.GetPosition(),task.GetZoom()); Cache::Instance()->ImageCache.PutImageToCache(task.GetImg(),task.GetMapType(),task.GetPosition(),task.GetZoom());
QThread::usleep(44); QThread::usleep(44);
} }
@ -52,13 +95,18 @@ void TileCacheQueue::run()
if(!wait.wait(&waitmutex,4444)) if(!wait.wait(&waitmutex,4444))
{ {
#ifdef DEBUG_TILECACHEQUEUE
qDebug()<<"Cache Engine TimeOut"; qDebug()<<"Cache Engine TimeOut";
#endif //DEBUG_TILECACHEQUEUE
if(tileCacheQueue.count()==0) break; if(tileCacheQueue.count()==0) break;
} }
waitmutex.unlock(); waitmutex.unlock();
} }
} }
#ifdef DEBUG_TILECACHEQUEUE
qDebug()<<"Cache Engine Stopped"; qDebug()<<"Cache Engine Stopped";
#endif //DEBUG_TILECACHEQUEUE
} }
}

View File

@ -1,3 +1,30 @@
/**
******************************************************************************
*
* @file tilecachequeue.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef TILECACHEQUEUE_H #ifndef TILECACHEQUEUE_H
#define TILECACHEQUEUE_H #define TILECACHEQUEUE_H
@ -11,6 +38,8 @@
#include "pureimagecache.h" #include "pureimagecache.h"
#include "cache.h" #include "cache.h"
namespace core {
class TileCacheQueue:public QThread class TileCacheQueue:public QThread
{ {
Q_OBJECT Q_OBJECT
@ -33,4 +62,5 @@ private:
}
#endif // TILECACHEQUEUE_H #endif // TILECACHEQUEUE_H

View File

@ -1,5 +1,34 @@
/**
******************************************************************************
*
* @file urlfactory.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "urlfactory.h" #include "urlfactory.h"
namespace core {
UrlFactory::UrlFactory() UrlFactory::UrlFactory()
{ {
/// <summary> /// <summary>
@ -68,7 +97,9 @@ void UrlFactory::TryCorrectGoogleVersions()
QNetworkRequest qheader; QNetworkRequest qheader;
QNetworkAccessManager network; QNetworkAccessManager network;
network.setProxy(Proxy); network.setProxy(Proxy);
#ifdef DEBUG_URLFACTORY
qDebug()<<"Correct GoogleVersion"; qDebug()<<"Correct GoogleVersion";
#endif //DEBUG_URLFACTORY
setIsCorrectGoogleVersions(true); setIsCorrectGoogleVersions(true);
QString url = "http://maps.google.com"; QString url = "http://maps.google.com";
@ -78,14 +109,20 @@ void UrlFactory::TryCorrectGoogleVersions()
QTime time; QTime time;
time.start(); time.start();
while( (!(reply->isFinished()) || (time.elapsed()>(6*Timeout))) ){QCoreApplication::processEvents(QEventLoop::AllEvents);} while( (!(reply->isFinished()) || (time.elapsed()>(6*Timeout))) ){QCoreApplication::processEvents(QEventLoop::AllEvents);}
#ifdef DEBUG_URLFACTORY
qDebug()<<"Finished?"<<reply->error()<<" abort?"<<(time.elapsed()>Timeout*6); qDebug()<<"Finished?"<<reply->error()<<" abort?"<<(time.elapsed()>Timeout*6);
#endif //DEBUG_URLFACTORY
if( (reply->error()!=QNetworkReply::NoError) | (time.elapsed()>Timeout*6)) if( (reply->error()!=QNetworkReply::NoError) | (time.elapsed()>Timeout*6))
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<"Try corrected version network error:"; qDebug()<<"Try corrected version network error:";
#endif //DEBUG_URLFACTORY
return; return;
} }
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<"Try corrected version withou abort or error:"<<reply->errorString(); qDebug()<<"Try corrected version withou abort or error:"<<reply->errorString();
#endif //DEBUG_URLFACTORY
QString html=QString(reply->readAll()); QString html=QString(reply->readAll());
// find it // find it
// apiCallback(["http://mt0.google.com/vt/v\x3dw2.106\x26hl\x3dlt\x26","http://mt1.google.com/vt/v\x3dw2.106\x26hl\x3dlt\x26","http://mt2.google.com/vt/v\x3dw2.106\x26hl\x3dlt\x26","http://mt3.google.com/vt/v\x3dw2.106\x26hl\x3dlt\x26"], // apiCallback(["http://mt0.google.com/vt/v\x3dw2.106\x26hl\x3dlt\x26","http://mt1.google.com/vt/v\x3dw2.106\x26hl\x3dlt\x26","http://mt2.google.com/vt/v\x3dw2.106\x26hl\x3dlt\x26","http://mt3.google.com/vt/v\x3dw2.106\x26hl\x3dlt\x26"],
@ -122,12 +159,16 @@ void UrlFactory::TryCorrectGoogleVersions()
{ {
if(u.startsWith("m@")) if(u.startsWith("m@"))
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<("TryCorrectGoogleVersions[map]: " + u); qDebug()<<("TryCorrectGoogleVersions[map]: " + u);
#endif //DEBUG_URLFACTORY
VersionGoogleMap = u; VersionGoogleMap = u;
} }
else else
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<("TryCorrectGoogleVersions[map FAILED]: " + u); qDebug()<<("TryCorrectGoogleVersions[map FAILED]: " + u);
#endif //DEBUG_URLFACTORY
} }
} }
else else
@ -136,12 +177,16 @@ void UrlFactory::TryCorrectGoogleVersions()
// 45 // 45
if(u[0].isDigit()) if(u[0].isDigit())
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<("TryCorrectGoogleVersions[satelite]: " + u); qDebug()<<("TryCorrectGoogleVersions[satelite]: " + u);
#endif //DEBUG_URLFACTORY
VersionGoogleSatellite = u; VersionGoogleSatellite = u;
} }
else else
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<("TryCorrectGoogleVersions[satelite FAILED]: " + u); qDebug()<<("TryCorrectGoogleVersions[satelite FAILED]: " + u);
#endif //DEBUG_URLFACTORY
} }
} }
else else
@ -149,12 +194,16 @@ void UrlFactory::TryCorrectGoogleVersions()
{ {
if(u.startsWith("h@")) if(u.startsWith("h@"))
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<("TryCorrectGoogleVersions[labels]: " + u); qDebug()<<("TryCorrectGoogleVersions[labels]: " + u);
#endif //DEBUG_URLFACTORY
VersionGoogleLabels = u; VersionGoogleLabels = u;
} }
else else
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<("TryCorrectGoogleVersions[labels FAILED]: " + u); qDebug()<<("TryCorrectGoogleVersions[labels FAILED]: " + u);
#endif //DEBUG_URLFACTORY
} }
} }
else else
@ -163,13 +212,17 @@ void UrlFactory::TryCorrectGoogleVersions()
// t@108,r@120 // t@108,r@120
if(u.startsWith("t@")) if(u.startsWith("t@"))
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<("TryCorrectGoogleVersions[terrain]: " + u); qDebug()<<("TryCorrectGoogleVersions[terrain]: " + u);
#endif //DEBUG_URLFACTORY
VersionGoogleTerrain = u; VersionGoogleTerrain = u;
VersionGoogleTerrainChina = u; VersionGoogleTerrainChina = u;
} }
else else
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<("TryCorrectGoogleVersions[terrain FAILED]: " + u); qDebug()<<("TryCorrectGoogleVersions[terrain FAILED]: " + u);
#endif //DEBUG_URLFACTORY
} }
break; break;
} }
@ -187,7 +240,9 @@ void UrlFactory::TryCorrectGoogleVersions()
} }
QString UrlFactory::MakeImageUrl(const MapType::Types &type,const Point &pos,const int &zoom,const QString &language) QString UrlFactory::MakeImageUrl(const MapType::Types &type,const Point &pos,const int &zoom,const QString &language)
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<"Entered MakeImageUrl"; qDebug()<<"Entered MakeImageUrl";
#endif //DEBUG_URLFACTORY
switch(type) switch(type)
{ {
case MapType::GoogleMap: case MapType::GoogleMap:
@ -517,7 +572,9 @@ PointLatLng UrlFactory::GetLatLngFromGeodecoder(const QString &keywords, GeoCode
} }
PointLatLng UrlFactory::GetLatLngFromGeocoderUrl(const QString &url, const bool &useCache, GeoCoderStatusCode::Types &status) PointLatLng UrlFactory::GetLatLngFromGeocoderUrl(const QString &url, const bool &useCache, GeoCoderStatusCode::Types &status)
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<"Entered GetLatLngFromGeocoderUrl:"; qDebug()<<"Entered GetLatLngFromGeocoderUrl:";
#endif //DEBUG_URLFACTORY
status = GeoCoderStatusCode::Unknow; status = GeoCoderStatusCode::Unknow;
PointLatLng ret(0,0); PointLatLng ret(0,0);
QString urlEnd = url.right(url.indexOf("geo?q=")); QString urlEnd = url.right(url.indexOf("geo?q="));
@ -535,7 +592,9 @@ PointLatLng UrlFactory::GetLatLngFromGeocoderUrl(const QString &url, const bool
if(geo.isNull()|geo.isEmpty()) if(geo.isNull()|geo.isEmpty())
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<"GetLatLngFromGeocoderUrl:Not in cache going internet"; qDebug()<<"GetLatLngFromGeocoderUrl:Not in cache going internet";
#endif //DEBUG_URLFACTORY
QNetworkReply *reply; QNetworkReply *reply;
QNetworkRequest qheader; QNetworkRequest qheader;
QNetworkAccessManager network; QNetworkAccessManager network;
@ -543,18 +602,26 @@ PointLatLng UrlFactory::GetLatLngFromGeocoderUrl(const QString &url, const bool
qheader.setUrl(QUrl(url)); qheader.setUrl(QUrl(url));
qheader.setRawHeader("User-Agent",UserAgent); qheader.setRawHeader("User-Agent",UserAgent);
reply=network.get(qheader); reply=network.get(qheader);
#ifdef DEBUG_URLFACTORY
qDebug()<<"GetLatLngFromGeocoderUrl:URL="<<url; qDebug()<<"GetLatLngFromGeocoderUrl:URL="<<url;
#endif //DEBUG_URLFACTORY
QTime time; QTime time;
time.start(); time.start();
while( (!(reply->isFinished()) || (time.elapsed()>(6*Timeout))) ){QCoreApplication::processEvents(QEventLoop::AllEvents);} while( (!(reply->isFinished()) || (time.elapsed()>(6*Timeout))) ){QCoreApplication::processEvents(QEventLoop::AllEvents);}
#ifdef DEBUG_URLFACTORY
qDebug()<<"Finished?"<<reply->error()<<" abort?"<<(time.elapsed()>Timeout*6); qDebug()<<"Finished?"<<reply->error()<<" abort?"<<(time.elapsed()>Timeout*6);
#endif //DEBUG_URLFACTORY
if( (reply->error()!=QNetworkReply::NoError) | (time.elapsed()>Timeout*6)) if( (reply->error()!=QNetworkReply::NoError) | (time.elapsed()>Timeout*6))
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<"GetLatLngFromGeocoderUrl::Network error"; qDebug()<<"GetLatLngFromGeocoderUrl::Network error";
#endif //DEBUG_URLFACTORY
return PointLatLng(0,0); return PointLatLng(0,0);
} }
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<"GetLatLngFromGeocoderUrl:Reply ok"; qDebug()<<"GetLatLngFromGeocoderUrl:Reply ok";
#endif //DEBUG_URLFACTORY
geo=reply->readAll(); geo=reply->readAll();
@ -582,7 +649,9 @@ PointLatLng UrlFactory::GetLatLngFromGeocoderUrl(const QString &url, const bool
double lng = QString(values[3]).toDouble(); double lng = QString(values[3]).toDouble();
ret = PointLatLng(lat, lng); ret = PointLatLng(lat, lng);
#ifdef DEBUG_URLFACTORY
qDebug()<<"Lat="<<lat<<" Lng="<<lng; qDebug()<<"Lat="<<lat<<" Lng="<<lng;
#endif //DEBUG_URLFACTORY
} }
} }
} }
@ -598,7 +667,9 @@ Placemark UrlFactory::GetPlacemarkFromReverseGeocoderUrl(const QString &url, con
{ {
Placemark ret(""); Placemark ret("");
#ifdef DEBUG_URLFACTORY
qDebug()<<"Entered GetPlacemarkFromReverseGeocoderUrl:"; qDebug()<<"Entered GetPlacemarkFromReverseGeocoderUrl:";
#endif //DEBUG_URLFACTORY
// status = GeoCoderStatusCode::Unknow; // status = GeoCoderStatusCode::Unknow;
QString urlEnd = url.right(url.indexOf("geo?hl=")); QString urlEnd = url.right(url.indexOf("geo?hl="));
urlEnd.replace( QRegExp( urlEnd.replace( QRegExp(
@ -615,7 +686,9 @@ Placemark UrlFactory::GetPlacemarkFromReverseGeocoderUrl(const QString &url, con
if(reverse.isNull()|reverse.isEmpty()) if(reverse.isNull()|reverse.isEmpty())
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<"GetLatLngFromGeocoderUrl:Not in cache going internet"; qDebug()<<"GetLatLngFromGeocoderUrl:Not in cache going internet";
#endif //DEBUG_URLFACTORY
QNetworkReply *reply; QNetworkReply *reply;
QNetworkRequest qheader; QNetworkRequest qheader;
QNetworkAccessManager network; QNetworkAccessManager network;
@ -623,22 +696,32 @@ Placemark UrlFactory::GetPlacemarkFromReverseGeocoderUrl(const QString &url, con
qheader.setUrl(QUrl(url)); qheader.setUrl(QUrl(url));
qheader.setRawHeader("User-Agent",UserAgent); qheader.setRawHeader("User-Agent",UserAgent);
reply=network.get(qheader); reply=network.get(qheader);
#ifdef DEBUG_URLFACTORY
qDebug()<<"GetLatLngFromGeocoderUrl:URL="<<url; qDebug()<<"GetLatLngFromGeocoderUrl:URL="<<url;
#endif //DEBUG_URLFACTORY
QTime time; QTime time;
time.start(); time.start();
while( (!(reply->isFinished()) || (time.elapsed()>(6*Timeout))) ){QCoreApplication::processEvents(QEventLoop::AllEvents);} while( (!(reply->isFinished()) || (time.elapsed()>(6*Timeout))) ){QCoreApplication::processEvents(QEventLoop::AllEvents);}
#ifdef DEBUG_URLFACTORY
qDebug()<<"Finished?"<<reply->error()<<" abort?"<<(time.elapsed()>Timeout*6); qDebug()<<"Finished?"<<reply->error()<<" abort?"<<(time.elapsed()>Timeout*6);
#endif //DEBUG_URLFACTORY
if( (reply->error()!=QNetworkReply::NoError) | (time.elapsed()>Timeout*6)) if( (reply->error()!=QNetworkReply::NoError) | (time.elapsed()>Timeout*6))
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<"GetLatLngFromGeocoderUrl::Network error"; qDebug()<<"GetLatLngFromGeocoderUrl::Network error";
#endif //DEBUG_URLFACTORY
return ret; return ret;
} }
{ {
#ifdef DEBUG_URLFACTORY
qDebug()<<"GetLatLngFromGeocoderUrl:Reply ok"; qDebug()<<"GetLatLngFromGeocoderUrl:Reply ok";
#endif //DEBUG_URLFACTORY
QByteArray a=(reply->readAll()); QByteArray a=(reply->readAll());
QTextCodec *codec = QTextCodec::codecForName("UTF-8"); QTextCodec *codec = QTextCodec::codecForName("UTF-8");
reverse = codec->toUnicode(a); reverse = codec->toUnicode(a);
#ifdef DEBUG_URLFACTORY
qDebug()<<reverse; qDebug()<<reverse;
#endif //DEBUG_URLFACTORY
// cache geocoding // cache geocoding
if(useCache && reverse.startsWith("200")) if(useCache && reverse.startsWith("200"))
{ {
@ -674,3 +757,4 @@ double UrlFactory::GetDistance(PointLatLng p1, PointLatLng p2)
double dDistance = EarthRadiusKm * c; double dDistance = EarthRadiusKm * c;
return dDistance; return dDistance;
} }
}

View File

@ -1,3 +1,30 @@
/**
******************************************************************************
*
* @file urlfactory.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef URLFACTORY_H #ifndef URLFACTORY_H
#define URLFACTORY_H #define URLFACTORY_H
@ -17,6 +44,10 @@
#include "placemark.h" #include "placemark.h"
#include <QTextCodec> #include <QTextCodec>
#include "cmath" #include "cmath"
using namespace internals;
namespace core {
class UrlFactory: public QObject,public ProviderStrings class UrlFactory: public QObject,public ProviderStrings
{ {
Q_OBJECT Q_OBJECT
@ -57,4 +88,5 @@ protected:
Placemark GetPlacemarkFromReverseGeocoderUrl(const QString &url,const bool &useCache); Placemark GetPlacemarkFromReverseGeocoderUrl(const QString &url,const bool &useCache);
}; };
}
#endif // URLFACTORY_H #endif // URLFACTORY_H

View File

@ -32,13 +32,13 @@ int main(int argc, char *argv[])
PureImageCache* p=new PureImageCache(); PureImageCache* p=new PureImageCache();
QPixmap pixmap; QPixmap pixmap;
//Tile Polling test //Tile Polling test
pixmap=PureImageProxy::FromStream(GMaps::Instance()->GetImageFrom(MapType::GoogleSatellite,Point(1,0),1)); pixmap=PureImageProxy::FromStream(OPMaps::Instance()->GetImageFrom(MapType::GoogleSatellite,Point(1,0),1));
QLabel label; QLabel label;
label.setPixmap(pixmap); label.setPixmap(pixmap);
label.show(); label.show();
//Geocoding Test //Geocoding Test
GeoCoderStatusCode::Types status; GeoCoderStatusCode::Types status;
qDebug()<<"Lisbon Coordinates:"<<GMaps::Instance()->GetLatLngFromGeodecoder("lisbon",status).ToString(); qDebug()<<"Lisbon Coordinates:"<<OPMaps::Instance()->GetLatLngFromGeodecoder("lisbon",status).ToString();
return a.exec(); return a.exec();
} }

View File

@ -1,4 +1,34 @@
/**
******************************************************************************
*
* @file MouseWheelZoomType.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "mousewheelzoomtype.h" #include "mousewheelzoomtype.h"
namespace internals {
QStringList MouseWheelZoomType::strList=QStringList()<<"MousePositionAndCenter"<<"MousePositionWithoutCenter"<<"ViewCenter"; QStringList MouseWheelZoomType::strList=QStringList()<<"MousePositionAndCenter"<<"MousePositionWithoutCenter"<<"ViewCenter";
}

View File

@ -1,12 +1,42 @@
/**
******************************************************************************
*
* @file copyrightstrings.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef COPYRIGHTSTRINGS_H #ifndef COPYRIGHTSTRINGS_H
#define COPYRIGHTSTRINGS_H #define COPYRIGHTSTRINGS_H
#include <QString> #include <QString>
#include <QDateTime> #include <QDateTime>
namespace internals {
static const QString googleCopyright = QString("©%1 Google - Map data ©%1 Tele Atlas, Imagery ©%1 TerraMetrics").arg(QDate::currentDate().year()); static const QString googleCopyright = QString("©%1 Google - Map data ©%1 Tele Atlas, Imagery ©%1 TerraMetrics").arg(QDate::currentDate().year());
static const QString openStreetMapCopyright = QString("© OpenStreetMap - Map data ©%1 OpenStreetMap").arg(QDate::currentDate().year()); static const QString openStreetMapCopyright = QString("© OpenStreetMap - Map data ©%1 OpenStreetMap").arg(QDate::currentDate().year());
static const QString yahooMapCopyright = QString("© Yahoo! Inc. - Map data & Imagery ©%1 NAVTEQ").arg(QDate::currentDate().year()); static const QString yahooMapCopyright = QString("© Yahoo! Inc. - Map data & Imagery ©%1 NAVTEQ").arg(QDate::currentDate().year());
static const QString virtualEarthCopyright = QString("©%1 Microsoft Corporation, ©%1 NAVTEQ, ©%1 Image courtesy of NASA").arg(QDate::currentDate().year()); static const QString virtualEarthCopyright = QString("©%1 Microsoft Corporation, ©%1 NAVTEQ, ©%1 Image courtesy of NASA").arg(QDate::currentDate().year());
static const QString arcGisCopyright = QString("©%1 ESRI - Map data ©%1 ArcGIS").arg(QDate::currentDate().year()); static const QString arcGisCopyright = QString("©%1 ESRI - Map data ©%1 ArcGIS").arg(QDate::currentDate().year());
}
#endif // COPYRIGHTSTRINGS_H #endif // COPYRIGHTSTRINGS_H

View File

@ -1,5 +1,37 @@
/**
******************************************************************************
*
* @file core.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "core.h" #include "core.h"
qlonglong internals::Core::debugcounter=0;
using namespace projections;
namespace internals {
Core::Core():currentPosition(0,0),currentPositionPixel(0,0),LastLocationInBounds(-1,-1),sizeOfMapArea(0,0) Core::Core():currentPosition(0,0),currentPositionPixel(0,0),LastLocationInBounds(-1,-1),sizeOfMapArea(0,0)
,minOfTiles(0,0),maxOfTiles(0,0),isDragging(false),started(false),MouseWheelZooming(false),TooltipTextPadding(10,10),zoom(0),loaderLimit(5) ,minOfTiles(0,0),maxOfTiles(0,0),isDragging(false),started(false),MouseWheelZooming(false),TooltipTextPadding(10,10),zoom(0),loaderLimit(5)
{ {
@ -12,7 +44,14 @@ Core::Core():currentPosition(0,0),currentPositionPixel(0,0),LastLocationInBounds
} }
void Core::run() void Core::run()
{ {
qDebug()<<"core:run"; qlonglong debug;
Mdebug.lock();
debug=++debugcounter;
Mdebug.unlock();
#ifdef DEBUG_CORE
qDebug()<<"core:run"<<" ID="<<debug;
#endif //DEBUG_CORE
bool last = false; bool last = false;
LoadTask task; LoadTask task;
@ -24,26 +63,34 @@ void Core::run()
task = tileLoadQueue.dequeue(); task = tileLoadQueue.dequeue();
{ {
last = tileLoadQueue.count() == 0; last = tileLoadQueue.count() == 0;
qDebug()<<"TileLoadQueue: " << tileLoadQueue.count()<<" Point:"<<task.Pos.ToString(); #ifdef DEBUG_CORE
qDebug()<<"TileLoadQueue: " << tileLoadQueue.count()<<" Point:"<<task.Pos.ToString()<<" ID="<<debug;;
#endif //DEBUG_CORE
} }
} }
} }
MtileLoadQueue.unlock(); MtileLoadQueue.unlock();
if(loaderLimit.tryAcquire(1,GMaps::Instance()->Timeout)) if(loaderLimit.tryAcquire(1,OPMaps::Instance()->Timeout))
{ {
#ifdef DEBUG_CORE
qDebug()<<"loadLimit semaphore aquired "<<loaderLimit.available()<<" ID="<<debug<<" TASK="<<task.Pos.ToString()<<" "<<task.Zoom;
#endif //DEBUG_CORE
if(task.HasValue()) if(task.HasValue())
{ {
qDebug()<<"AKI"; #ifdef DEBUG_CORE
qDebug()<<"task as value, begining get"<<" ID="<<debug;;
#endif //DEBUG_CORE
{ {
Tile* m = Matrix.TileAt(task.Pos); Tile* m = Matrix.TileAt(task.Pos);
if(m==0 || m->Overlays.count() == 0) if(m==0 || m->Overlays.count() == 0)
{ {
qDebug()<<"Fill empty TileMatrix: " + task.ToString(); #ifdef DEBUG_CORE
qDebug()<<"Fill empty TileMatrix: " + task.ToString()<<" ID="<<debug;;
#endif //DEBUG_CORE
Tile* t = new Tile(task.Zoom, task.Pos); Tile* t = new Tile(task.Zoom, task.Pos);
QVector<MapType::Types> layers= GMaps::Instance()->GetAllLayersOfType(GetMapType()); QVector<MapType::Types> layers= OPMaps::Instance()->GetAllLayersOfType(GetMapType());
foreach(MapType::Types tl,layers) foreach(MapType::Types tl,layers)
{ {
@ -55,12 +102,15 @@ void Core::run()
// tile number inversion(BottomLeft -> TopLeft) for pergo maps // tile number inversion(BottomLeft -> TopLeft) for pergo maps
if(tl == MapType::PergoTurkeyMap) if(tl == MapType::PergoTurkeyMap)
{ {
img = GMaps::Instance()->GetImageFrom(tl, Point(task.Pos.X(), maxOfTiles.Height() - task.Pos.Y()), task.Zoom); img = OPMaps::Instance()->GetImageFrom(tl, Point(task.Pos.X(), maxOfTiles.Height() - task.Pos.Y()), task.Zoom);
} }
else // ok else // ok
{ {
img = GMaps::Instance()->GetImageFrom(tl, task.Pos, task.Zoom); qDebug()<<"start getting image"<<" ID="<<debug;
qDebug()<<"Core::run:gotimage size:"<<img.count(); img = OPMaps::Instance()->GetImageFrom(tl, task.Pos, task.Zoom);
#ifdef DEBUG_CORE
qDebug()<<"Core::run:gotimage size:"<<img.count()<<" ID="<<debug;
#endif //DEBUG_CORE
} }
if(img.length()!=0) if(img.length()!=0)
@ -68,15 +118,20 @@ void Core::run()
Moverlays.lock(); Moverlays.lock();
{ {
t->Overlays.append(img); t->Overlays.append(img);
qDebug()<<"Core::run append img:"<<img.length()<<" to tile:"<<t->GetPos().ToString()<<" now has "<<t->Overlays.count()<<" overlays"; #ifdef DEBUG_CORE
qDebug()<<"Core::run append img:"<<img.length()<<" to tile:"<<t->GetPos().ToString()<<" now has "<<t->Overlays.count()<<" overlays"<<" ID="<<debug;
#endif //DEBUG_CORE
} }
Moverlays.unlock(); Moverlays.unlock();
break; break;
} }
else if(GMaps::Instance()->RetryLoadTile > 0) else if(OPMaps::Instance()->RetryLoadTile > 0)
{ {
qDebug()<<"ProcessLoadTask: " << task.ToString()<< " -> empty tile, retry " << retry; #ifdef DEBUG_CORE
qDebug()<<"ProcessLoadTask: " << task.ToString()<< " -> empty tile, retry " << retry<<" ID="<<debug;;
#endif //DEBUG_CORE
{ {
QWaitCondition wait; QWaitCondition wait;
QMutex m; QMutex m;
@ -85,14 +140,17 @@ void Core::run()
} }
} }
} }
while(++retry < GMaps::Instance()->RetryLoadTile); while(++retry < OPMaps::Instance()->RetryLoadTile);
} }
if(t->Overlays.count() > 0) if(t->Overlays.count() > 0)
{ {
Matrix.SetTileAt(task.Pos,t); Matrix.SetTileAt(task.Pos,t);
qDebug()<<"Core::run add tile "<<t->GetPos().ToString()<<" to matrix index "<<task.Pos.ToString(); emit OnNeedInvalidation();
qDebug()<<"Core::run matrix index "<<task.Pos.ToString()<<" as tile with "<<Matrix.TileAt(task.Pos)->Overlays.count(); #ifdef DEBUG_CORE
qDebug()<<"Core::run add tile "<<t->GetPos().ToString()<<" to matrix index "<<task.Pos.ToString()<<" ID="<<debug;
qDebug()<<"Core::run matrix index "<<task.Pos.ToString()<<" as tile with "<<Matrix.TileAt(task.Pos)->Overlays.count()<<" ID="<<debug;
#endif //DEBUG_CORE
} }
else else
{ {
@ -109,9 +167,9 @@ void Core::run()
// last buddy cleans stuff ;} // last buddy cleans stuff ;}
if(last) if(last)
{ {
GMaps::Instance()->kiberCacheLock.lockForWrite(); OPMaps::Instance()->kiberCacheLock.lockForWrite();
GMaps::Instance()->TilesInMemory.RemoveMemoryOverload(); OPMaps::Instance()->TilesInMemory.RemoveMemoryOverload();
GMaps::Instance()->kiberCacheLock.unlock(); OPMaps::Instance()->kiberCacheLock.unlock();
MtileDrawingList.lock(); MtileDrawingList.lock();
{ {
@ -127,8 +185,12 @@ void Core::run()
} }
} }
loaderLimit.release();
} }
qDebug()<<"loaderLimit release:"+loaderLimit.available()<<" ID="<<debug;
loaderLimit.release();
} }
} }
void Core::SetZoom(const int &value) void Core::SetZoom(const int &value)
@ -311,7 +373,7 @@ void Core::OnMapClose()
GeoCoderStatusCode::Types Core::SetCurrentPositionByKeywords(QString const& keys) GeoCoderStatusCode::Types Core::SetCurrentPositionByKeywords(QString const& keys)
{ {
GeoCoderStatusCode::Types status = GeoCoderStatusCode::Unknow; GeoCoderStatusCode::Types status = GeoCoderStatusCode::Unknow;
PointLatLng pos = GMaps::Instance()->GetLatLngFromGeodecoder(keys, status); PointLatLng pos = OPMaps::Instance()->GetLatLngFromGeodecoder(keys, status);
if(pos.IsEmpty() && status == GeoCoderStatusCode::G_GEO_SUCCESS) if(pos.IsEmpty() && status == GeoCoderStatusCode::G_GEO_SUCCESS)
{ {
SetCurrentPosition(pos); SetCurrentPosition(pos);
@ -343,7 +405,7 @@ int Core::GetMaxZoomToFitRect(RectLatLng const& rect)
{ {
int zoom = 0; int zoom = 0;
for(int i = 1; i <= GMaps::Instance()->MaxZoom; i++) for(int i = 1; i <= OPMaps::Instance()->MaxZoom; i++)
{ {
Point p1 = Projection()->FromLatLngToPixel(rect.LocationTopLeft(), i); Point p1 = Projection()->FromLatLngToPixel(rect.LocationTopLeft(), i);
Point p2 = Projection()->FromLatLngToPixel(rect.Bottom(), rect.Right(), i); Point p2 = Projection()->FromLatLngToPixel(rect.Bottom(), rect.Right(), i);
@ -376,7 +438,9 @@ void Core::ReloadMap()
{ {
if(started) if(started)
{ {
#ifdef DEBUG_CORE
qDebug()<<"------------------"; qDebug()<<"------------------";
#endif //DEBUG_CORE
MtileLoadQueue.lock(); MtileLoadQueue.lock();
{ {
@ -482,12 +546,13 @@ void Core::CancelAsyncTasks()
{ {
if(started) if(started)
{ {
ProcessLoadTaskCallback.waitForDone();
MtileLoadQueue.lock(); MtileLoadQueue.lock();
{ {
tileLoadQueue.clear(); tileLoadQueue.clear();
} }
MtileLoadQueue.unlock(); MtileLoadQueue.unlock();
ProcessLoadTaskCallback.waitForDone(); // ProcessLoadTaskCallback.waitForDone();
} }
} }
void Core::UpdateBounds() void Core::UpdateBounds()
@ -496,7 +561,9 @@ void Core::UpdateBounds()
{ {
FindTilesAround(tileDrawingList); FindTilesAround(tileDrawingList);
#ifdef DEBUG_CORE
qDebug()<<"OnTileLoadStart: " << tileDrawingList.count() << " tiles to load at zoom " << Zoom() << ", time: " << QDateTime::currentDateTime().date(); qDebug()<<"OnTileLoadStart: " << tileDrawingList.count() << " tiles to load at zoom " << Zoom() << ", time: " << QDateTime::currentDateTime().date();
#endif //DEBUG_CORE
emit OnTileLoadStart(); emit OnTileLoadStart();
@ -510,7 +577,9 @@ void Core::UpdateBounds()
if(!tileLoadQueue.contains(task)) if(!tileLoadQueue.contains(task))
{ {
tileLoadQueue.enqueue(task); tileLoadQueue.enqueue(task);
#ifdef DEBUG_CORE
qDebug()<<"Core::UpdateBounds new Task"<<task.Pos.ToString(); qDebug()<<"Core::UpdateBounds new Task"<<task.Pos.ToString();
#endif //DEBUG_CORE
ProcessLoadTaskCallback.start(this); ProcessLoadTaskCallback.start(this);
} }
} }
@ -565,3 +634,4 @@ void Core::UpdateGroundResolution()
pxRes1000km = (int) (1000000.0 / rez); // 1000km pxRes1000km = (int) (1000000.0 / rez); // 1000km
pxRes5000km = (int) (5000000.0 / rez); // 5000km pxRes5000km = (int) (5000000.0 / rez); // 5000km
} }
}

View File

@ -1,6 +1,37 @@
/**
******************************************************************************
*
* @file core.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef CORE_H #ifndef CORE_H
#define CORE_H #define CORE_H
#define DEBUG_CORE
//#define DEBUG_TILE
//#define DEBUG_TILEMATRIX
#include "../internals/PointLatlng.h" #include "../internals/PointLatlng.h"
#include "mousewheelzoomtype.h" #include "mousewheelzoomtype.h"
#include "../core/size.h" #include "../core/size.h"
@ -25,13 +56,15 @@
//#include <QObject> //#include <QObject>
namespace internals {
class Core:public QObject,public QRunnable class Core:public QObject,public QRunnable
{ {
Q_OBJECT Q_OBJECT
public: public:
Core(); Core();
void run(); void run();
PointLatLng CurrentPosition(){return currentPosition;}; PointLatLng CurrentPosition()const{return currentPosition;};
void SetCurrentPosition(const PointLatLng &value); void SetCurrentPosition(const PointLatLng &value);
Point GetcurrentPositionGPixel(){return currentPositionPixel;}; Point GetcurrentPositionGPixel(){return currentPositionPixel;};
@ -95,7 +128,7 @@ public:
} }
bool IsDragging()const{return isDragging;} bool IsDragging()const{return isDragging;}
int Zoom(){return zoom;} int Zoom()const{return zoom;}
void SetZoom(int const& value); void SetZoom(int const& value);
@ -150,6 +183,8 @@ public:
Point mouseDown; Point mouseDown;
bool CanDragMap; bool CanDragMap;
Point mouseCurrent; Point mouseCurrent;
PointLatLng LastLocationInBounds;
Point mouseLastZoom;
signals: signals:
void OnCurrentPositionChanged(PointLatLng point); void OnCurrentPositionChanged(PointLatLng point);
void OnTileLoadComplete(); void OnTileLoadComplete();
@ -162,6 +197,7 @@ signals:
private: private:
static qlonglong debugcounter;
PointLatLng currentPosition; PointLatLng currentPosition;
Point currentPositionPixel; Point currentPositionPixel;
Point renderOffset; Point renderOffset;
@ -170,10 +206,8 @@ private:
Point dragPoint; Point dragPoint;
Point mouseLastZoom;
MouseWheelZoomType::Types mousewheelzoomtype; MouseWheelZoomType::Types mousewheelzoomtype;
PointLatLng LastLocationInBounds;
Size sizeOfMapArea; Size sizeOfMapArea;
Size minOfTiles; Size minOfTiles;
@ -200,6 +234,8 @@ private:
QMutex MtileDrawingList; QMutex MtileDrawingList;
QMutex Mdebug;
Size TooltipTextPadding; Size TooltipTextPadding;
MapType::Types mapType; MapType::Types mapType;
@ -224,4 +260,5 @@ protected:
}; };
}
#endif // CORE_H #endif // CORE_H

View File

@ -1,6 +1,36 @@
/**
******************************************************************************
*
* @file loadtask.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "loadtask.h" #include "loadtask.h"
namespace internals {
bool operator==(LoadTask const& lhs,LoadTask const& rhs) bool operator==(LoadTask const& lhs,LoadTask const& rhs)
{ {
return ((lhs.Pos==rhs.Pos)&&(lhs.Zoom==rhs.Zoom)); return ((lhs.Pos==rhs.Pos)&&(lhs.Zoom==rhs.Zoom));
} }
}

View File

@ -1,9 +1,39 @@
/**
******************************************************************************
*
* @file loadtask.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef LOADTASK_H #ifndef LOADTASK_H
#define LOADTASK_H #define LOADTASK_H
#include <QString> #include <QString>
#include "../core/point.h" #include "../core/point.h"
using namespace core;
namespace internals
{
struct LoadTask struct LoadTask
{ {
friend bool operator==(LoadTask const& lhs,LoadTask const& rhs); friend bool operator==(LoadTask const& lhs,LoadTask const& rhs);
@ -32,4 +62,5 @@ struct LoadTask
return QString::number(Zoom) + " - " + Pos.ToString(); return QString::number(Zoom) + " - " + Pos.ToString();
} }
}; };
}
#endif // LOADTASK_H #endif // LOADTASK_H

View File

@ -1,8 +1,37 @@
/**
******************************************************************************
*
* @file mousewheelzoomtype.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef MOUSEWHEELZOOMTYPE_H #ifndef MOUSEWHEELZOOMTYPE_H
#define MOUSEWHEELZOOMTYPE_H #define MOUSEWHEELZOOMTYPE_H
#include <QObject> #include <QObject>
#include <QStringList> #include <QStringList>
#include <QMetaType> #include <QMetaType>
namespace internals {
struct MouseWheelZoomType struct MouseWheelZoomType
{ {
enum Types enum Types
@ -28,6 +57,8 @@ struct MouseWheelZoomType
private: private:
static QStringList strList; static QStringList strList;
}; };
Q_DECLARE_METATYPE(MouseWheelZoomType::Types)
}
Q_DECLARE_METATYPE(internals::MouseWheelZoomType::Types)
#endif // MOUSEWHEELZOOMTYPE_H #endif // MOUSEWHEELZOOMTYPE_H

View File

@ -1,5 +1,34 @@
/**
******************************************************************************
*
* @file pointlatlng.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "pointlatlng.h" #include "pointlatlng.h"
namespace internals {
PointLatLng PointLatLng::Empty=PointLatLng(); PointLatLng PointLatLng::Empty=PointLatLng();
PointLatLng::PointLatLng():lat(0),lng(0),empty(true) PointLatLng::PointLatLng():lat(0),lng(0),empty(true)
{ {
@ -24,3 +53,4 @@ PointLatLng operator-(PointLatLng pt, SizeLatLng sz)
{ {
return PointLatLng::Subtract(pt, sz); return PointLatLng::Subtract(pt, sz);
} }
}

View File

@ -1,9 +1,38 @@
/**
******************************************************************************
*
* @file pointlatlng.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef POINTLATLNG_H #ifndef POINTLATLNG_H
#define POINTLATLNG_H #define POINTLATLNG_H
#include <QHash> #include <QHash>
#include <QString> #include <QString>
#include "sizelatlng.h" #include "sizelatlng.h"
namespace internals {
struct PointLatLng struct PointLatLng
{ {
//friend uint qHash(PointLatLng const& point); //friend uint qHash(PointLatLng const& point);
@ -98,4 +127,5 @@ struct PointLatLng
// //
}
#endif // POINTLATLNG_H #endif // POINTLATLNG_H

View File

@ -1,6 +1,35 @@
/**
******************************************************************************
*
* @file lks94projection.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "lks94projection.h" #include "lks94projection.h"
namespace projections {
LKS94Projection::LKS94Projection():MinLatitude (53.33 ), MaxLatitude (56.55 ), MinLongitude (20.22 ), LKS94Projection::LKS94Projection():MinLatitude (53.33 ), MaxLatitude (56.55 ), MinLongitude (20.22 ),
MaxLongitude (27.11 ), orignX (5122000 ), orignY (10000100 ),tileSize(256, 256) MaxLongitude (27.11 ), orignX (5122000 ), orignY (10000100 ),tileSize(256, 256)
{ {
@ -755,3 +784,4 @@ Size LKS94Projection::GetTileMatrixMaxXY(int const& zoom)
return ret; return ret;
} }
}

View File

@ -1,10 +1,40 @@
/**
******************************************************************************
*
* @file lks94projection.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef LKS94PROJECTION_H #ifndef LKS94PROJECTION_H
#define LKS94PROJECTION_H #define LKS94PROJECTION_H
#include <QVector> #include <QVector>
#include "cmath" #include "cmath"
#include "../internals/pureprojection.h" #include "../internals/pureprojection.h"
class LKS94Projection:public PureProjection using namespace internals;
namespace projections {
class LKS94Projection:public internals::PureProjection
{ {
public: public:
LKS94Projection(); LKS94Projection();
@ -36,6 +66,7 @@ private:
double Clip(double const& n, double const& minValue, double const& maxValue); double Clip(double const& n, double const& minValue, double const& maxValue);
}; };
}
#endif // LKS94PROJECTION_H #endif // LKS94PROJECTION_H

View File

@ -1,5 +1,34 @@
/**
******************************************************************************
*
* @file mercatorprojection.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "mercatorprojection.h" #include "mercatorprojection.h"
namespace projections {
MercatorProjection::MercatorProjection():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-177), MercatorProjection::MercatorProjection():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-177),
MaxLongitude(177), tileSize(256, 256) MaxLongitude(177), tileSize(256, 256)
{ {
@ -65,3 +94,4 @@ Size MercatorProjection::GetTileMatrixMinXY(const int &zoom)
{ {
return Size(0, 0); return Size(0, 0);
} }
}

View File

@ -1,7 +1,38 @@
/**
******************************************************************************
*
* @file mercatorprojection.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef MERCATORPROJECTION_H #ifndef MERCATORPROJECTION_H
#define MERCATORPROJECTION_H #define MERCATORPROJECTION_H
#include "../internals/pureprojection.h" #include "../internals/pureprojection.h"
class MercatorProjection:public PureProjection
using namespace internals;
namespace projections {
class MercatorProjection:public internals::PureProjection
{ {
public: public:
MercatorProjection(); MercatorProjection();
@ -22,4 +53,5 @@ private:
Size tileSize; Size tileSize;
}; };
}
#endif // MERCATORPROJECTION_H #endif // MERCATORPROJECTION_H

View File

@ -1,6 +1,35 @@
/**
******************************************************************************
*
* @file mercatorprojectionyandex.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "mercatorprojectionyandex.h" #include "mercatorprojectionyandex.h"
namespace projections {
MercatorProjectionYandex::MercatorProjectionYandex():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-177), MercatorProjectionYandex::MercatorProjectionYandex():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-177),
MaxLongitude(177), tileSize(256, 256),RAD_DEG(180 / M_PI),DEG_RAD(M_PI / 180), MathPiDiv4(M_PI / 4) MaxLongitude(177), tileSize(256, 256),RAD_DEG(180 / M_PI),DEG_RAD(M_PI / 180), MathPiDiv4(M_PI / 4)
{ {
@ -80,3 +109,4 @@ Size MercatorProjectionYandex::GetTileMatrixMinXY(const int &zoom)
{ {
return Size(0, 0); return Size(0, 0);
} }
}

View File

@ -1,8 +1,38 @@
/**
******************************************************************************
*
* @file mercatorprojectionyandex.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef MERCATORPROJECTIONYANDEX_H #ifndef MERCATORPROJECTIONYANDEX_H
#define MERCATORPROJECTIONYANDEX_H #define MERCATORPROJECTIONYANDEX_H
#include "../internals/pureprojection.h" #include "../internals/pureprojection.h"
using namespace internals;
namespace projections {
class MercatorProjectionYandex:public PureProjection class MercatorProjectionYandex:public PureProjection
{ {
public: public:
@ -27,4 +57,5 @@ private:
Size tileSize; Size tileSize;
}; };
}
#endif // MERCATORPROJECTIONYANDEX_H #endif // MERCATORPROJECTIONYANDEX_H

View File

@ -1,6 +1,35 @@
/**
******************************************************************************
*
* @file platecarreeprojection.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "platecarreeprojection.h" #include "platecarreeprojection.h"
namespace projections {
PlateCarreeProjection::PlateCarreeProjection():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-180), PlateCarreeProjection::PlateCarreeProjection():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-180),
MaxLongitude(180), tileSize(512, 512) MaxLongitude(180), tileSize(512, 512)
{ {
@ -65,3 +94,4 @@ Size PlateCarreeProjection::GetTileMatrixMinXY(const int &zoom)
{ {
return Size(0, 0); return Size(0, 0);
} }
}

View File

@ -1,8 +1,38 @@
/**
******************************************************************************
*
* @file platecarreeprojection.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PLATECARREEPROJECTION_H #ifndef PLATECARREEPROJECTION_H
#define PLATECARREEPROJECTION_H #define PLATECARREEPROJECTION_H
#include "../internals/pureprojection.h" #include "../internals/pureprojection.h"
using namespace internals;
namespace projections {
class PlateCarreeProjection:public PureProjection class PlateCarreeProjection:public PureProjection
{ {
public: public:
@ -24,4 +54,5 @@ private:
double Clip(double const& n, double const& minValue, double const& maxValue)const; double Clip(double const& n, double const& minValue, double const& maxValue)const;
Size tileSize; Size tileSize;
}; };
}
#endif // PLATECARREEPROJECTION_H #endif // PLATECARREEPROJECTION_H

View File

@ -1,5 +1,34 @@
/**
******************************************************************************
*
* @file platecarreeprojectionpergo.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "platecarreeprojectionpergo.h" #include "platecarreeprojectionpergo.h"
namespace projections {
PlateCarreeProjectionPergo::PlateCarreeProjectionPergo():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-180), PlateCarreeProjectionPergo::PlateCarreeProjectionPergo():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-180),
MaxLongitude(180), tileSize(256, 256) MaxLongitude(180), tileSize(256, 256)
{ {
@ -64,3 +93,4 @@ Size PlateCarreeProjectionPergo::GetTileMatrixMinXY(const int &zoom)
{ {
return Size(0, 0); return Size(0, 0);
} }
}

View File

@ -1,8 +1,38 @@
/**
******************************************************************************
*
* @file platecarreeprojectionpergo.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PLATECARREEPROJECTIONPERGO_H #ifndef PLATECARREEPROJECTIONPERGO_H
#define PLATECARREEPROJECTIONPERGO_H #define PLATECARREEPROJECTIONPERGO_H
#include "../internals/pureprojection.h" #include "../internals/pureprojection.h"
using namespace internals;
namespace projections {
class PlateCarreeProjectionPergo:public PureProjection class PlateCarreeProjectionPergo:public PureProjection
{ {
public: public:
@ -24,4 +54,5 @@ private:
double Clip(double const& n, double const& minValue, double const& maxValue)const; double Clip(double const& n, double const& minValue, double const& maxValue)const;
Size tileSize; Size tileSize;
}; };
}
#endif // PLATECARREEPROJECTIONPERGO_H #endif // PLATECARREEPROJECTIONPERGO_H

View File

@ -1,9 +1,38 @@
/**
******************************************************************************
*
* @file pureprojection.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "pureprojection.h" #include "pureprojection.h"
namespace internals {
Point PureProjection::FromLatLngToPixel(const PointLatLng::PointLatLng &p,const int &zoom) Point PureProjection::FromLatLngToPixel(const PointLatLng::PointLatLng &p,const int &zoom)
{ {
return FromLatLngToPixel(p.Lat(), p.Lng(), zoom); return FromLatLngToPixel(p.Lat(), p.Lng(), zoom);
@ -176,3 +205,4 @@ Point PureProjection::FromLatLngToPixel(const PointLatLng::PointLatLng &p,const
Lat /= (PI / 180); Lat /= (PI / 180);
Lng /= (PI / 180); Lng /= (PI / 180);
} }
}

View File

@ -1,3 +1,30 @@
/**
******************************************************************************
*
* @file pureprojection.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PUREPROJECTION_H #ifndef PUREPROJECTION_H
#define PUREPROJECTION_H #define PUREPROJECTION_H
@ -7,6 +34,12 @@
#include "pointlatlng.h" #include "pointlatlng.h"
#include "cmath" #include "cmath"
#include "rectlatlng.h" #include "rectlatlng.h"
using namespace core;
namespace internals
{
class PureProjection class PureProjection
{ {
@ -72,7 +105,7 @@ protected:
static qlonglong GetUTMzone(const double &lon); static qlonglong GetUTMzone(const double &lon);
}; };
}
#endif // PUREPROJECTION_H #endif // PUREPROJECTION_H

View File

@ -1,5 +1,33 @@
/**
******************************************************************************
*
* @file rectangle.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "rectangle.h" #include "rectangle.h"
namespace internals {
Rectangle Rectangle::Empty=Rectangle(); Rectangle Rectangle::Empty=Rectangle();
Rectangle Rectangle::FromLTRB(int left, int top, int right, int bottom) Rectangle Rectangle::FromLTRB(int left, int top, int right, int bottom)
{ {
@ -49,3 +77,4 @@ uint qHash(Rectangle const& rect)
(((quint32) rect.width << 26) | ((quint32) rect.width >> 6)) ^ (((quint32) rect.width << 26) | ((quint32) rect.width >> 6)) ^
(((quint32) rect.height << 7) | ((quint32) rect.height >> 25))); (((quint32) rect.height << 7) | ((quint32) rect.height >> 25)));
} }
}

View File

@ -1,11 +1,41 @@
/**
******************************************************************************
*
* @file rectangle.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef RECTANGLE_H #ifndef RECTANGLE_H
#define RECTANGLE_H #define RECTANGLE_H
//#include <point.h> //#include <point.h>
#include "../core/size.h" #include "../core/size.h"
#include "math.h" #include "math.h"
using namespace core;
namespace internals
{
struct Rectangle struct Rectangle
{ {
friend uint qHash(Rectangle const& rect); friend uint qHash(Rectangle const& rect);
friend bool operator==(Rectangle const& lhs,Rectangle const& rhs); friend bool operator==(Rectangle const& lhs,Rectangle const& rhs);
public: public:
@ -125,5 +155,5 @@ private:
int width; int width;
int height; int height;
}; };
}
#endif // RECTANGLE_H #endif // RECTANGLE_H

View File

@ -1,6 +1,35 @@
/**
******************************************************************************
*
* @file rectlatlng.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "rectlatlng.h" #include "rectlatlng.h"
namespace internals {
RectLatLng RectLatLng::Empty=RectLatLng(); RectLatLng RectLatLng::Empty=RectLatLng();
uint qHash(RectLatLng const& rect) uint qHash(RectLatLng const& rect)
{ {
@ -17,3 +46,4 @@ bool operator!=(RectLatLng const& left,RectLatLng const& right)
return !(left == right); return !(left == right);
} }
}

View File

@ -1,3 +1,30 @@
/**
******************************************************************************
*
* @file rectlatlng.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef RECTLATLNG_H #ifndef RECTLATLNG_H
#define RECTLATLNG_H #define RECTLATLNG_H
@ -6,6 +33,8 @@
#include "math.h" #include "math.h"
#include <QString> #include <QString>
#include "sizelatlng.h" #include "sizelatlng.h"
namespace internals {
struct RectLatLng struct RectLatLng
{ {
public: public:
@ -224,6 +253,7 @@ private:
bool isempty; bool isempty;
}; };
}
#endif // RECTLATLNG_H #endif // RECTLATLNG_H

View File

@ -1,5 +1,34 @@
/**
******************************************************************************
*
* @file sizelatlng.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "sizelatlng.h" #include "sizelatlng.h"
#include "pointlatlng.h" #include "pointlatlng.h"
namespace internals {
SizeLatLng::SizeLatLng():heightLat(0),widthLng(0) SizeLatLng::SizeLatLng():heightLat(0),widthLng(0)
{ {
@ -29,3 +58,4 @@ bool operator!=(SizeLatLng const& sz1, SizeLatLng const& sz2)
return !(sz1 == sz2); return !(sz1 == sz2);
} }
SizeLatLng SizeLatLng::Empty=SizeLatLng(); SizeLatLng SizeLatLng::Empty=SizeLatLng();
}

View File

@ -1,9 +1,38 @@
/**
******************************************************************************
*
* @file sizelatlng.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef SIZELATLNG_H #ifndef SIZELATLNG_H
#define SIZELATLNG_H #define SIZELATLNG_H
#include <QString> #include <QString>
namespace internals {
struct PointLatLng; struct PointLatLng;
struct SizeLatLng struct SizeLatLng
{ {
@ -103,5 +132,6 @@ private:
double widthLng; double widthLng;
}; };
}
#endif // SIZELATLNG_H #endif // SIZELATLNG_H

View File

@ -1,5 +1,34 @@
/**
******************************************************************************
*
* @file tile.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "tile.h" #include "tile.h"
namespace internals {
Tile::Tile(int zoom, Point pos) Tile::Tile(int zoom, Point pos)
{ {
this->zoom=zoom; this->zoom=zoom;
@ -7,7 +36,9 @@ Tile::Tile(int zoom, Point pos)
} }
void Tile::Clear() void Tile::Clear()
{ {
#ifdef DEBUG_TILE
qDebug()<<"Tile:Clear Overlays"; qDebug()<<"Tile:Clear Overlays";
#endif //DEBUG_TILE
mutex.lock(); mutex.lock();
foreach(QByteArray img, Overlays) foreach(QByteArray img, Overlays)
{ {
@ -27,3 +58,4 @@ Tile& Tile::operator =(const Tile &cSource)
return *this; return *this;
} }
}

View File

@ -1,3 +1,30 @@
/**
******************************************************************************
*
* @file tile.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef TILE_H #ifndef TILE_H
#define TILE_H #define TILE_H
@ -6,6 +33,9 @@
#include "../core/point.h" #include "../core/point.h"
#include <QMutex> #include <QMutex>
#include <QDebug> #include <QDebug>
using namespace core;
namespace internals
{
class Tile class Tile
{ {
public: public:
@ -33,5 +63,5 @@ private:
}; };
}
#endif // TILE_H #endif // TILE_H

View File

@ -1,5 +1,34 @@
/**
******************************************************************************
*
* @file tilematrix.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "tilematrix.h" #include "tilematrix.h"
namespace internals {
TileMatrix::TileMatrix() TileMatrix::TileMatrix()
{ {
} }
@ -45,7 +74,9 @@ void TileMatrix::ClearPointsNotIn(QList<Point>list)
Tile* TileMatrix::TileAt(const Point &p) Tile* TileMatrix::TileAt(const Point &p)
{ {
#ifdef DEBUG_TILEMATRIX
qDebug()<<"TileMatrix:TileAt:"<<p.ToString(); qDebug()<<"TileMatrix:TileAt:"<<p.ToString();
#endif //DEBUG_TILEMATRIX
Tile* ret; Tile* ret;
mutex.lock(); mutex.lock();
ret=matrix.value(p,0); ret=matrix.value(p,0);
@ -58,3 +89,4 @@ void TileMatrix::SetTileAt(const Point &p, Tile* tile)
matrix.insert(p,tile); matrix.insert(p,tile);
mutex.unlock(); mutex.unlock();
} }
}

View File

@ -1,3 +1,30 @@
/**
******************************************************************************
*
* @file tilematrix.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup OPMapWidget
* @{
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef TILEMATRIX_H #ifndef TILEMATRIX_H
#define TILEMATRIX_H #define TILEMATRIX_H
@ -5,6 +32,8 @@
#include "tile.h" #include "tile.h"
#include <QList> #include <QList>
#include "../core/point.h" #include "../core/point.h"
namespace internals {
class TileMatrix class TileMatrix
{ {
public: public:
@ -13,10 +42,12 @@ public:
void ClearPointsNotIn(QList<Point> list); void ClearPointsNotIn(QList<Point> list);
Tile* TileAt(const Point &p); Tile* TileAt(const Point &p);
void SetTileAt(const Point &p,Tile* tile); void SetTileAt(const Point &p,Tile* tile);
int count()const{return matrix.count();}
protected: protected:
QHash<Point,Tile*> matrix; QHash<Point,Tile*> matrix;
QList<Point> removals; QList<Point> removals;
QMutex mutex; QMutex mutex;
}; };
}
#endif // TILEMATRIX_H #endif // TILEMATRIX_H

View File

@ -1,6 +1,6 @@
#include "opmapcontrol.h" #include "opmapcontrol.h"
OPMapControl::OPMapControl(QWidget *parent):QWidget(parent),MapRenderTransform(1), maxZoom(2),minZoom(2),zoomReal(0),isSelected(false) OPMapControl::OPMapControl(QWidget *parent):QWidget(parent),MapRenderTransform(1), maxZoom(17),minZoom(2),zoomReal(0),isSelected(false)
{ {
EmptytileBrush = Qt::cyan; EmptytileBrush = Qt::cyan;
MissingDataFont =QFont ("Times",10,QFont::Bold); MissingDataFont =QFont ("Times",10,QFont::Bold);
@ -56,6 +56,7 @@ void OPMapControl::paintEvent(QPaintEvent* evnt)
void OPMapControl::DrawMap2D(QPainter &painter) void OPMapControl::DrawMap2D(QPainter &painter)
{ {
qDebug()<<core.Matrix.count();
// painter.drawText(10,10,"TESTE"); // painter.drawText(10,10,"TESTE");
for(int i = -core.GetsizeOfMapArea().Width(); i <= core.GetsizeOfMapArea().Width(); i++) for(int i = -core.GetsizeOfMapArea().Width(); i <= core.GetsizeOfMapArea().Width(); i++)
{ {
@ -72,7 +73,7 @@ void OPMapControl::DrawMap2D(QPainter &painter)
//Tile t = Core.Matrix[tileToDraw]; //Tile t = Core.Matrix[tileToDraw];
if(t!=0) if(t!=0)
{ {
qDebug()<< "opmapcontrol:draw2d TileHasValue:"<<t->GetPos().ToString(); //qDebug()<< "opmapcontrol:draw2d TileHasValue:"<<t->GetPos().ToString();
core.tileRect.SetX(core.GettilePoint().X()*core.tileRect.Width()); core.tileRect.SetX(core.GettilePoint().X()*core.tileRect.Width());
core.tileRect.SetY(core.GettilePoint().Y()*core.tileRect.Height()); core.tileRect.SetY(core.GettilePoint().Y()*core.tileRect.Height());
core.tileRect.Offset(core.GetrenderOffset()); core.tileRect.Offset(core.GetrenderOffset());
@ -106,7 +107,7 @@ void OPMapControl::DrawMap2D(QPainter &painter)
painter.setFont(MissingDataFont); painter.setFont(MissingDataFont);
painter.setPen(Qt::red); painter.setPen(Qt::red);
painter.drawText(QRectF(core.tileRect.X(), core.tileRect.Y(), core.tileRect.Width(), core.tileRect.Height()),Qt::AlignCenter,(core.GettilePoint() == core.GetcenterTileXYLocation()? "CENTER: " :"TILE: ")+core.GettilePoint().ToString()); painter.drawText(QRectF(core.tileRect.X(), core.tileRect.Y(), core.tileRect.Width(), core.tileRect.Height()),Qt::AlignCenter,(core.GettilePoint() == core.GetcenterTileXYLocation()? "CENTER: " :"TILE: ")+core.GettilePoint().ToString());
qDebug()<<"ShowTileGridLine:"<<core.GettilePoint().ToString()<<"=="<<core.GetcenterTileXYLocation().ToString(); //qDebug()<<"ShowTileGridLine:"<<core.GettilePoint().ToString()<<"=="<<core.GetcenterTileXYLocation().ToString();
} }
} }
@ -171,6 +172,37 @@ PointLatLng OPMapControl::FromLocalToLatLng(int x, int y)
} }
void OPMapControl::mouseReleaseEvent ( QMouseEvent* evnt ) void OPMapControl::mouseReleaseEvent ( QMouseEvent* evnt )
{ {
QWidget::mouseReleaseEvent(evnt);
if(isSelected)
{
isSelected = false;
}
if(core.IsDragging())
{
core.EndDrag();
this->setCursor(Qt::ArrowCursor);
if(!BoundsOfMap.IsEmpty() && !BoundsOfMap.Contains(CurrentPosition()))
{
if(!core.LastLocationInBounds.IsEmpty())
{
SetCurrentPosition(core.LastLocationInBounds);
}
}
}
else
{
if(!selectionEnd.IsEmpty() && !selectionStart.IsEmpty())
{
if(!SelectedArea().IsEmpty() && evnt->modifiers() == Qt::ShiftModifier)
{
// SetZoomToFitRect(SelectedArea());TODO
}
}
}
} }
@ -202,6 +234,123 @@ void OPMapControl::resize()
core.GoToCurrentPosition(); core.GoToCurrentPosition();
} }
} }
void OPMapControl::wheelEvent(QWheelEvent *event)
{
QWidget::wheelEvent(event);
if(!IsMouseOverMarker() && !IsDragging())
{
if(core.GetmouseLastZoom().X() != event->pos().x() && core.mouseLastZoom.Y() != event->pos().y())
{
if(GetMouseWheelZoomType() == MouseWheelZoomType::MousePositionAndCenter)
{
core.SetCurrentPosition(FromLocalToLatLng(event->pos().x(), event->pos().y()));
}
else if(GetMouseWheelZoomType() == MouseWheelZoomType::ViewCenter)
{
core.SetCurrentPosition(FromLocalToLatLng((int) width()/2, (int) height()/2));
}
else if(GetMouseWheelZoomType() == MouseWheelZoomType::MousePositionWithoutCenter)
{
core.SetCurrentPosition(FromLocalToLatLng(event->pos().x(), event->pos().y()));
}
core.mouseLastZoom.SetX((event->pos().x()));
core.mouseLastZoom.SetY((event->pos().y()));
}
// set mouse position to map center
if(GetMouseWheelZoomType() != MouseWheelZoomType::MousePositionWithoutCenter)
{
{
// System.Drawing.Point p = PointToScreen(new System.Drawing.Point(Width/2, Height/2));
// Stuff.SetCursorPos((int) p.X, (int) p.Y);
}
}
core.MouseWheelZooming = true;
if(event->delta() > 0)
{
SetZoom(Zoom()+1);
}
else if(event->delta() < 0)
{
SetZoom(Zoom()-1);
}
core.MouseWheelZooming = false;
}
}
double OPMapControl::Zoom()
{
return zoomReal;
}
void OPMapControl::SetZoom(double const& value)
{
if(zoomReal != value)
{
if(value > MaxZoom())
{
zoomReal = MaxZoom();
}
else
if(value < MinZoom())
{
zoomReal = MinZoom();
}
else
{
zoomReal = value;
}
float remainder = (float)std::fmod((float) value, (float) 1);
if(remainder != 0)
{
float scaleValue = remainder + 1;
{
MapRenderTransform = scaleValue;
}
SetZoomStep((qint32)(value - remainder));
this->repaint();
}
else
{
MapRenderTransform = 1;
SetZoomStep ((qint32)(value));
zoomReal = ZoomStep();
this->repaint();
}
}
}
int OPMapControl::ZoomStep()const
{
return core.Zoom();
}
void OPMapControl::SetZoomStep(int const& value)
{
if(value > MaxZoom())
{
core.SetZoom(MaxZoom());
}
else if(value < MinZoom())
{
core.SetZoom(MinZoom());
}
else
{
core.SetZoom(value);
}
}
void OPMapControl::Offset(int const& x, int const& y) void OPMapControl::Offset(int const& x, int const& y)
{ {
core.DragOffset(Point(x, y)); core.DragOffset(Point(x, y));

View File

@ -7,15 +7,20 @@
#include <QWidget> #include <QWidget>
#include <QBrush> #include <QBrush>
#include <QFont> #include <QFont>
using namespace core;
//using namespace internals;
class OPMapControl:public QWidget class OPMapControl:public QWidget
{ {
Q_OBJECT Q_OBJECT
Q_PROPERTY(int MaxZoom READ MaxZoom WRITE SetMaxZoom) Q_PROPERTY(int MaxZoom READ MaxZoom WRITE SetMaxZoom)
Q_PROPERTY(int MinZoom READ MinZoom WRITE SetMinZoom) Q_PROPERTY(int MinZoom READ MinZoom WRITE SetMinZoom)
Q_PROPERTY(MouseWheelZoomType::Types MouseWheelZoom READ GetMouseWheelZoomType WRITE SetMouseWheelZoomType) Q_PROPERTY(internals::MouseWheelZoomType::Types MouseWheelZoom READ GetMouseWheelZoomType WRITE SetMouseWheelZoomType)
Q_PROPERTY(QString MouseWheelZoomStr READ GetMouseWheelZoomTypeStr WRITE SetMouseWheelZoomTypeByStr) Q_PROPERTY(QString MouseWheelZoomStr READ GetMouseWheelZoomTypeStr WRITE SetMouseWheelZoomTypeByStr)
Q_PROPERTY(bool ShowTileGridLines READ ShowTileGridLines WRITE SetShowTileGridLines) Q_PROPERTY(bool ShowTileGridLines READ ShowTileGridLines WRITE SetShowTileGridLines)
Q_PROPERTY(double Zoom READ Zoom WRITE SetZoom)
public: public:
OPMapControl(QWidget *parent=0); OPMapControl(QWidget *parent=0);
QBrush EmptytileBrush; QBrush EmptytileBrush;
@ -41,7 +46,10 @@ public:
void Offset(int const& x, int const& y); void Offset(int const& x, int const& y);
bool CanDragMap()const{return core.CanDragMap;} bool CanDragMap()const{return core.CanDragMap;}
void SetCanDragMap(bool const& value){core.CanDragMap = value;} void SetCanDragMap(bool const& value){core.CanDragMap = value;}
PointLatLng CurrentPosition()const{return core.CurrentPosition();}
void SetCurrentPosition(PointLatLng const& value){core.SetCurrentPosition(value);}
double Zoom();
void SetZoom(double const& value);
protected: protected:
void paintEvent ( QPaintEvent* evnt ); void paintEvent ( QPaintEvent* evnt );
void mousePressEvent ( QMouseEvent* evnt ); void mousePressEvent ( QMouseEvent* evnt );
@ -52,7 +60,9 @@ protected:
void closeEvent ( QCloseEvent * event ); void closeEvent ( QCloseEvent * event );
bool IsDragging()const{return core.IsDragging();} bool IsDragging()const{return core.IsDragging();}
bool IsMouseOverMarker()const{return isMouseOverMarker;} bool IsMouseOverMarker()const{return isMouseOverMarker;}
void wheelEvent ( QWheelEvent * event );
int ZoomStep()const;
void SetZoomStep(int const& value);
private: private:
bool showTileGridLines; bool showTileGridLines;
Core core; Core core;

View File

@ -25,10 +25,15 @@
#include "../core/size.h" #include "../core/size.h"
#include "../internals/copyrightstrings.h" #include "../internals/copyrightstrings.h"
#include "../internals/projections/lks94projection.h" #include "../internals/projections/lks94projection.h"
using namespace core;
using namespace internals;
using namespace projections;
int main(int argc, char *argv[]) int main(int argc, char *argv[])
{ {
QApplication a(argc, argv); QApplication a(argc, argv);
// GMaps g; // OPMaps g;
// qDebug()<<g.GoogleMapsAPIKey; // qDebug()<<g.GoogleMapsAPIKey;
// qDebug()<<QString(g.levelsForSigPacSpainMap[2]); // qDebug()<<QString(g.levelsForSigPacSpainMap[2]);
// qDebug()<<g.MakeImageUrl(GoogleMap,Point(18,10),5,QString("en")); // qDebug()<<g.MakeImageUrl(GoogleMap,Point(18,10),5,QString("en"));
@ -76,17 +81,17 @@ int main(int argc, char *argv[])
//// // QTest::qsleep(200); //// // QTest::qsleep(200);
//// queue.EnqueueCacheTask(item); //// queue.EnqueueCacheTask(item);
////} ////}
//pixmapb=PureImageProxy::FromStream(GMaps::Instance()->GetImageFrom(MapType::GoogleMap,Point(7,5),8)); //pixmapb=PureImageProxy::FromStream(OPMaps::Instance()->GetImageFrom(MapType::GoogleMap,Point(7,5),8));
//qDebug()<<"WITH"<<pixmapb.width(); //qDebug()<<"WITH"<<pixmapb.width();
labell.setPixmap(pixmapb); labell.setPixmap(pixmapb);
//// ////
labell.show(); labell.show();
// QCoreApplication::processEvents(QEventLoop::AllEvents); // QCoreApplication::processEvents(QEventLoop::AllEvents);
////pixmapb=GMaps::Instance()->GetImageFrom(MapType::GoogleSatellite,Point(1,0),1); ////pixmapb=OPMaps::Instance()->GetImageFrom(MapType::GoogleSatellite,Point(1,0),1);
////labell.setPixmap(pixmapb); ////labell.setPixmap(pixmapb);
////GeoCoderStatusCode::Types f; ////GeoCoderStatusCode::Types f;
////qDebug()<<"LAT"<<GMaps::Instance()->GetLatLngFromGeodecoder("lisbon",f).Lat(); ////qDebug()<<"LAT"<<OPMaps::Instance()->GetLatLngFromGeodecoder("lisbon",f).Lat();
////QString s=GMaps::Instance()->GetPlacemarkFromGeocoder(GMaps::Instance()->GetLatLngFromGeodecoder("lisbon",f)).Address(); ////QString s=OPMaps::Instance()->GetPlacemarkFromGeocoder(OPMaps::Instance()->GetLatLngFromGeodecoder("lisbon",f)).Address();
////labell.show(); ////labell.show();
////labell.setText(s); ////labell.setText(s);
//threadpool *g=new threadpool(); //threadpool *g=new threadpool();

View File

@ -1,3 +1,5 @@
#include <QApplication> #include <QApplication>
//#include "map.h" //#include "map.h"
#include "../mapwidget/opmapcontrol.h" #include "../mapwidget/opmapcontrol.h"