Commit 5856f869 authored by Gus Grubba's avatar Gus Grubba

Camera parameters caching.

parent 62c380c6
...@@ -12,6 +12,7 @@ ...@@ -12,6 +12,7 @@
#include "QGCMapEngine.h" #include "QGCMapEngine.h"
#include <QDir> #include <QDir>
#include <QStandardPaths>
#include <QDomDocument> #include <QDomDocument>
#include <QDomNodeList> #include <QDomNodeList>
...@@ -110,6 +111,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh ...@@ -110,6 +111,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
, _vehicle(vehicle) , _vehicle(vehicle)
, _compID(compID) , _compID(compID)
, _version(0) , _version(0)
, _cached(false)
, _storageFree(0) , _storageFree(0)
, _storageTotal(0) , _storageTotal(0)
, _netManager(NULL) , _netManager(NULL)
...@@ -121,7 +123,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh ...@@ -121,7 +123,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
const char* url = (const char*)info->cam_definition_uri; const char* url = (const char*)info->cam_definition_uri;
if(url[0] != 0) { if(url[0] != 0) {
//-- Process camera definition file //-- Process camera definition file
_httpRequest(url); _handleDefinitionFile(url);
} else { } else {
_initWhenReady(); _initWhenReady();
} }
...@@ -432,6 +434,7 @@ QGCCameraControl::_setVideoStatus(VideoStatus status) ...@@ -432,6 +434,7 @@ QGCCameraControl::_setVideoStatus(VideoStatus status)
bool bool
QGCCameraControl::_loadCameraDefinitionFile(QByteArray& bytes) QGCCameraControl::_loadCameraDefinitionFile(QByteArray& bytes)
{ {
QByteArray originalData(bytes);
//-- Handle localization //-- Handle localization
if(!_handleLocalization(bytes)) { if(!_handleLocalization(bytes)) {
return false; return false;
...@@ -456,6 +459,17 @@ QGCCameraControl::_loadCameraDefinitionFile(QByteArray& bytes) ...@@ -456,6 +459,17 @@ QGCCameraControl::_loadCameraDefinitionFile(QByteArray& bytes)
qWarning() << "Unable to load camera parameters from camera definition"; qWarning() << "Unable to load camera parameters from camera definition";
return false; return false;
} }
//-- If this is new, cache it
if(!_cached) {
QString cacheFile = _cacheFile();
qCDebug(CameraControlLog) << "Saving camera definition file" << cacheFile;
QFile file(cacheFile);
if (!file.open(QIODevice::WriteOnly)) {
qWarning() << QString("Could not save cache file %1. Error: %2").arg(cacheFile).arg(file.errorString());
} else {
file.write(originalData);
}
}
return true; return true;
} }
...@@ -1065,6 +1079,49 @@ QGCCameraControl::_loadNameValue(QDomNode option, const QString factName, FactMe ...@@ -1065,6 +1079,49 @@ QGCCameraControl::_loadNameValue(QDomNode option, const QString factName, FactMe
return true; return true;
} }
//-----------------------------------------------------------------------------
QString
QGCCameraControl::_cacheFile()
{
QString cacheFile;
cacheFile.sprintf("%s/%s_%s_%03d.xml",
qgcApp()->toolbox()->settingsManager()->appSettings()->parameterSavePath().toStdString().c_str(),
_info.vendor_name,
_info.model_name,
_info.cam_definition_version);
return cacheFile;
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_handleDefinitionFile(const QString &url)
{
//-- First check and see if we have it cached
QString cacheFile = _cacheFile();
QFile xmlFile(cacheFile);
if (!xmlFile.exists()) {
qCDebug(CameraControlLog) << "No camera definition file cached";
_httpRequest(url);
return;
}
if (!xmlFile.open(QIODevice::ReadOnly)) {
qWarning() << "Could not read cached camera definition file:" << cacheFile;
_httpRequest(url);
return;
}
QByteArray bytes = xmlFile.readAll();
QDomDocument doc;
if(!doc.setContent(bytes, false)) {
qWarning() << "Could not parse cached camera definition file:" << cacheFile;
_httpRequest(url);
return;
}
//-- We have it
qCDebug(CameraControlLog) << "Using cached camera definition file:" << cacheFile;
_cached = true;
emit dataReady(bytes);
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
QGCCameraControl::_httpRequest(const QString &url) QGCCameraControl::_httpRequest(const QString &url)
......
...@@ -183,15 +183,18 @@ private: ...@@ -183,15 +183,18 @@ private:
void _updateActiveList (); void _updateActiveList ();
void _updateRanges (Fact* pFact); void _updateRanges (Fact* pFact);
void _httpRequest (const QString& url); void _httpRequest (const QString& url);
void _handleDefinitionFile (const QString& url);
QStringList _loadExclusions (QDomNode option); QStringList _loadExclusions (QDomNode option);
QString _getParamName (const char* param_id); QString _getParamName (const char* param_id);
QString _cacheFile ();
protected: protected:
Vehicle* _vehicle; Vehicle* _vehicle;
int _compID; int _compID;
mavlink_camera_information_t _info; mavlink_camera_information_t _info;
int _version; int _version;
bool _cached;
uint32_t _storageFree; uint32_t _storageFree;
uint32_t _storageTotal; uint32_t _storageTotal;
QNetworkAccessManager* _netManager; QNetworkAccessManager* _netManager;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment