|
|
@ -11,6 +11,7 @@ |
|
|
|
#include "VideoManager.h" |
|
|
|
#include "VideoManager.h" |
|
|
|
#include "QGCMapEngine.h" |
|
|
|
#include "QGCMapEngine.h" |
|
|
|
#include "QGCCameraManager.h" |
|
|
|
#include "QGCCameraManager.h" |
|
|
|
|
|
|
|
#include "FTPManager.h" |
|
|
|
|
|
|
|
|
|
|
|
#include <QDir> |
|
|
|
#include <QDir> |
|
|
|
#include <QStandardPaths> |
|
|
|
#include <QStandardPaths> |
|
|
@ -1954,6 +1955,21 @@ QGCCameraControl::_handleDefinitionFile(const QString &url) |
|
|
|
{ |
|
|
|
{ |
|
|
|
//-- First check and see if we have it cached
|
|
|
|
//-- First check and see if we have it cached
|
|
|
|
QFile xmlFile(_cacheFile); |
|
|
|
QFile xmlFile(_cacheFile); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
QString ftpPrefix(QStringLiteral("%1://").arg(FTPManager::mavlinkFTPScheme)); |
|
|
|
|
|
|
|
if (url.startsWith(ftpPrefix, Qt::CaseInsensitive)) { |
|
|
|
|
|
|
|
int ver = static_cast<int>(_info.cam_definition_version); |
|
|
|
|
|
|
|
QString fileName = QString::asprintf("%s_%s_%03d.xml", |
|
|
|
|
|
|
|
_vendor.toStdString().c_str(), |
|
|
|
|
|
|
|
_modelName.toStdString().c_str(), |
|
|
|
|
|
|
|
ver); |
|
|
|
|
|
|
|
connect(_vehicle->ftpManager(), &FTPManager::downloadComplete, this, &QGCCameraControl::_ftpDownloadComplete); |
|
|
|
|
|
|
|
_vehicle->ftpManager()->download(url, |
|
|
|
|
|
|
|
qgcApp()->toolbox()->settingsManager()->appSettings()->parameterSavePath().toStdString().c_str(), |
|
|
|
|
|
|
|
fileName); |
|
|
|
|
|
|
|
return; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
if (!xmlFile.exists()) { |
|
|
|
if (!xmlFile.exists()) { |
|
|
|
qCDebug(CameraControlLog) << "No camera definition file cached"; |
|
|
|
qCDebug(CameraControlLog) << "No camera definition file cached"; |
|
|
|
_httpRequest(url); |
|
|
|
_httpRequest(url); |
|
|
@ -2024,6 +2040,26 @@ QGCCameraControl::_downloadFinished() |
|
|
|
//reply->deleteLater();
|
|
|
|
//reply->deleteLater();
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void QGCCameraControl::_ftpDownloadComplete(const QString& fileName, const QString& errorMsg) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
qCDebug(CameraControlLog) << "QGCCameraControl::_ftpDownloadComplete fileName:errorMsg" << fileName << errorMsg; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
disconnect(_vehicle->ftpManager(), &FTPManager::downloadComplete, this, &QGCCameraControl::_ftpDownloadComplete); |
|
|
|
|
|
|
|
QFile xmlFile(fileName); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (!xmlFile.exists()) { |
|
|
|
|
|
|
|
qCDebug(CameraControlLog) << "No camera definition file present after ftp download completed"; |
|
|
|
|
|
|
|
return; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
if (!xmlFile.open(QIODevice::ReadOnly)) { |
|
|
|
|
|
|
|
qWarning() << "Could not read downloaded camera definition file: " << fileName; |
|
|
|
|
|
|
|
return; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
QByteArray bytes = xmlFile.readAll(); |
|
|
|
|
|
|
|
emit dataReady(bytes); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
//-----------------------------------------------------------------------------
|
|
|
|
//-----------------------------------------------------------------------------
|
|
|
|
void |
|
|
|
void |
|
|
|
QGCCameraControl::_dataReady(QByteArray data) |
|
|
|
QGCCameraControl::_dataReady(QByteArray data) |
|
|
|