Commit c55af2f8 authored by Don Gagne's avatar Don Gagne

Handle redirects in file downloads

parent d24e93d6
......@@ -20,8 +20,12 @@ QGCFileDownload::QGCFileDownload(QObject* parent)
}
bool QGCFileDownload::download(const QString& remoteFile)
bool QGCFileDownload::download(const QString& remoteFile, bool redirect)
{
if (!redirect) {
_originalRemoteFile = remoteFile;
}
if (remoteFile.isEmpty()) {
qWarning() << "downloadFile empty";
return false;
......@@ -70,7 +74,7 @@ bool QGCFileDownload::download(const QString& remoteFile)
// Store local file location in user attribute so we can retrieve when the download finishes
networkRequest.setAttribute(QNetworkRequest::User, localFile);
QNetworkReply* networkReply = get(networkRequest);
if (!networkReply) {
qWarning() << "QNetworkAccessManager::get failed";
......@@ -94,7 +98,16 @@ void QGCFileDownload::_downloadFinished(void)
if (reply->error() != QNetworkReply::NoError) {
return;
}
// Check for redirection
QVariant redirectionTarget = reply->attribute(QNetworkRequest::RedirectionTargetAttribute);
if (!redirectionTarget.isNull()) {
QUrl redirectUrl = reply->url().resolved(redirectionTarget.toUrl());
download(redirectUrl.toString(), true /* redirect */);
reply->deleteLater();
return;
}
// Download file location is in user attribute
QString downloadFilename = reply->request().attribute(QNetworkRequest::User).toString();
Q_ASSERT(!downloadFilename.isEmpty());
......@@ -109,7 +122,7 @@ void QGCFileDownload::_downloadFinished(void)
file.write(reply->readAll());
file.close();
emit downloadFinished(reply->url().toString(), downloadFilename);
emit downloadFinished(_originalRemoteFile, downloadFilename);
}
/// @brief Called when an error occurs during download
......
......@@ -22,8 +22,9 @@ public:
/// Download the specified remote file.
/// @param remoteFile File to download. Can be http address or file system path.
/// @param redirect true: call is internal due to redirect
/// @return true: Asynchronous download has started, false: Download initialization failed
bool download(const QString& remoteFile);
bool download(const QString& remoteFile, bool redirect = false);
signals:
void downloadProgress(qint64 curr, qint64 total);
......@@ -33,6 +34,8 @@ signals:
private:
void _downloadFinished(void);
void _downloadError(QNetworkReply::NetworkError code);
QString _originalRemoteFile;
};
#endif
......@@ -545,52 +545,15 @@ void FirmwareUpgradeController::_downloadFirmware(void)
_appendStatusLog("Downloading firmware...");
_appendStatusLog(QString(" From: %1").arg(_firmwareFilename));
// Split out filename from path
QString firmwareFilename = QFileInfo(_firmwareFilename).fileName();
Q_ASSERT(!firmwareFilename.isEmpty());
// Determine location to download file to
QString downloadFile = QStandardPaths::writableLocation(QStandardPaths::TempLocation);
if (downloadFile.isEmpty()) {
downloadFile = QStandardPaths::writableLocation(QStandardPaths::DownloadLocation);
if (downloadFile.isEmpty()) {
_errorCancel("Unabled to find writable download location. Tried downloads and temp directory.");
return;
}
}
Q_ASSERT(!downloadFile.isEmpty());
downloadFile += "/" + firmwareFilename;
QUrl firmwareUrl;
if (_firmwareFilename.startsWith("http:")) {
firmwareUrl.setUrl(_firmwareFilename);
} else {
firmwareUrl = QUrl::fromLocalFile(_firmwareFilename);
}
Q_ASSERT(firmwareUrl.isValid());
QNetworkRequest networkRequest(firmwareUrl);
// Store download file location in user attribute so we can retrieve when the download finishes
networkRequest.setAttribute(QNetworkRequest::User, downloadFile);
_downloadManager = new QNetworkAccessManager(this);
Q_CHECK_PTR(_downloadManager);
QNetworkProxy tProxy;
tProxy.setType(QNetworkProxy::DefaultProxy);
_downloadManager->setProxy(tProxy);
_downloadNetworkReply = _downloadManager->get(networkRequest);
Q_ASSERT(_downloadNetworkReply);
connect(_downloadNetworkReply, &QNetworkReply::downloadProgress, this, &FirmwareUpgradeController::_downloadProgress);
connect(_downloadNetworkReply, &QNetworkReply::finished, this, &FirmwareUpgradeController::_downloadFinished);
connect(_downloadNetworkReply, static_cast<void (QNetworkReply::*)(QNetworkReply::NetworkError)>(&QNetworkReply::error),
this, &FirmwareUpgradeController::_downloadError);
QGCFileDownload* downloader = new QGCFileDownload(this);
connect(downloader, &QGCFileDownload::downloadFinished, this, &FirmwareUpgradeController::_firmwareDownloadFinished);
connect(downloader, &QGCFileDownload::downloadProgress, this, &FirmwareUpgradeController::_firmwareDownloadProgress);
connect(downloader, &QGCFileDownload::error, this, &FirmwareUpgradeController::_firmwareDownloadError);
downloader->download(_firmwareFilename);
}
/// @brief Updates the progress indicator while downloading
void FirmwareUpgradeController::_downloadProgress(qint64 curr, qint64 total)
void FirmwareUpgradeController::_firmwareDownloadProgress(qint64 curr, qint64 total)
{
// Take care of cases where 0 / 0 is emitted as error return value
if (total > 0) {
......@@ -599,43 +562,18 @@ void FirmwareUpgradeController::_downloadProgress(qint64 curr, qint64 total)
}
/// @brief Called when the firmware download completes.
void FirmwareUpgradeController::_downloadFinished(void)
void FirmwareUpgradeController::_firmwareDownloadFinished(QString remoteFile, QString localFile)
{
Q_UNUSED(remoteFile);
_appendStatusLog("Download complete");
QNetworkReply* reply = qobject_cast<QNetworkReply*>(QObject::sender());
Q_ASSERT(reply);
Q_ASSERT(_downloadNetworkReply == reply);
_downloadManager->deleteLater();
_downloadManager = NULL;
// When an error occurs or the user cancels the download, we still end up here. So bail out in
// those cases.
if (reply->error() != QNetworkReply::NoError) {
return;
}
// Download file location is in user attribute
QString downloadFilename = reply->request().attribute(QNetworkRequest::User).toString();
Q_ASSERT(!downloadFilename.isEmpty());
// Store downloaded file in download location
QFile file(downloadFilename);
if (!file.open(QIODevice::WriteOnly)) {
_errorCancel(QString("Could not save downloaded file to %1. Error: %2").arg(downloadFilename).arg(file.errorString()));
return;
}
file.write(reply->readAll());
file.close();
FirmwareImage* image = new FirmwareImage(this);
connect(image, &FirmwareImage::statusMessage, this, &FirmwareUpgradeController::_status);
connect(image, &FirmwareImage::errorMessage, this, &FirmwareUpgradeController::_error);
if (!image->load(downloadFilename, _bootloaderBoardID)) {
if (!image->load(localFile, _bootloaderBoardID)) {
_errorCancel("Image load failed");
return;
}
......@@ -655,20 +593,8 @@ void FirmwareUpgradeController::_downloadFinished(void)
}
/// @brief Called when an error occurs during download
void FirmwareUpgradeController::_downloadError(QNetworkReply::NetworkError code)
void FirmwareUpgradeController::_firmwareDownloadError(QString errorMsg)
{
QString errorMsg;
if (code == QNetworkReply::OperationCanceledError) {
errorMsg = "Download cancelled";
} else if (code == QNetworkReply::ContentNotFoundError) {
errorMsg = QString("Error: File Not Found. Please check %1 firmware version is available.")
.arg(firmwareTypeAsString(_selectedFirmwareType));
} else {
errorMsg = QString("Error during download. Error: %1").arg(code);
}
_errorCancel(errorMsg);
}
......
......@@ -155,9 +155,9 @@ signals:
void px4BetaVersionChanged(const QString& px4BetaVersion);
private slots:
void _downloadProgress(qint64 curr, qint64 total);
void _downloadFinished(void);
void _downloadError(QNetworkReply::NetworkError code);
void _firmwareDownloadProgress(qint64 curr, qint64 total);
void _firmwareDownloadFinished(QString remoteFile, QString localFile);
void _firmwareDownloadError(QString errorMsg);
void _foundBoard(bool firstAttempt, const QSerialPortInfo& portInfo, int boardType);
void _noBoardFound(void);
void _boardGone();
......
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