Unverified Commit 8fdbaf3f authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #8890 from DonLakeFlyer/CompInfoHTTP

COMPONENT_INFORMATION http download support
parents 80879792 52e3ff14
......@@ -219,56 +219,48 @@ void APMAirframeComponentController::loadParameters(const QString& paramFile)
QString paramFileUrl = QStringLiteral("https://api.github.com/repos/ArduPilot/ardupilot/contents/Tools/Frame_params/%1?ref=master");
QGCFileDownload* downloader = new QGCFileDownload(this);
connect(downloader, &QGCFileDownload::downloadFinished, this, &APMAirframeComponentController::_githubJsonDownloadFinished);
connect(downloader, &QGCFileDownload::error, this, &APMAirframeComponentController::_githubJsonDownloadError);
connect(downloader, &QGCFileDownload::downloadComplete, this, &APMAirframeComponentController::_githubJsonDownloadComplete);
downloader->download(paramFileUrl.arg(paramFile));
}
void APMAirframeComponentController::_githubJsonDownloadFinished(QString remoteFile, QString localFile)
void APMAirframeComponentController::_githubJsonDownloadComplete(QString /*remoteFile*/, QString localFile, QString errorMsg)
{
Q_UNUSED(remoteFile);
QFile jsonFile(localFile);
if (!jsonFile.open(QIODevice::ReadOnly | QIODevice::Text)) {
qWarning() << "Unable to open github json file" << localFile << jsonFile.errorString();
qgcApp()->restoreOverrideCursor();
return;
}
QByteArray bytes = jsonFile.readAll();
jsonFile.close();
if (errorMsg.isEmpty()) {
QFile jsonFile(localFile);
if (!jsonFile.open(QIODevice::ReadOnly | QIODevice::Text)) {
qWarning() << "Unable to open github json file" << localFile << jsonFile.errorString();
qgcApp()->restoreOverrideCursor();
return;
}
QByteArray bytes = jsonFile.readAll();
jsonFile.close();
QJsonParseError jsonParseError;
QJsonDocument doc = QJsonDocument::fromJson(bytes, &jsonParseError);
if (jsonParseError.error != QJsonParseError::NoError) {
qWarning() << "Unable to open json document" << localFile << jsonParseError.errorString();
qgcApp()->restoreOverrideCursor();
return;
}
QJsonObject json = doc.object();
QJsonParseError jsonParseError;
QJsonDocument doc = QJsonDocument::fromJson(bytes, &jsonParseError);
if (jsonParseError.error != QJsonParseError::NoError) {
qWarning() << "Unable to open json document" << localFile << jsonParseError.errorString();
QGCFileDownload* downloader = new QGCFileDownload(this);
connect(downloader, &QGCFileDownload::downloadComplete, this, &APMAirframeComponentController::_paramFileDownloadComplete);
downloader->download(json[QLatin1Literal("download_url")].toString());
} else {
qgcApp()->showAppMessage(tr("Param file github json download failed: %1").arg(errorMsg));
qgcApp()->restoreOverrideCursor();
return;
}
QJsonObject json = doc.object();
QGCFileDownload* downloader = new QGCFileDownload(this);
connect(downloader, &QGCFileDownload::downloadFinished, this, &APMAirframeComponentController::_paramFileDownloadFinished);
connect(downloader, &QGCFileDownload::error, this, &APMAirframeComponentController::_paramFileDownloadError);
downloader->download(json[QLatin1Literal("download_url")].toString());
}
void APMAirframeComponentController::_githubJsonDownloadError(QString errorMsg)
{
qgcApp()->showAppMessage(tr("Param file github json download failed: %1").arg(errorMsg));
qgcApp()->restoreOverrideCursor();
}
void APMAirframeComponentController::_paramFileDownloadFinished(QString remoteFile, QString localFile)
void APMAirframeComponentController::_paramFileDownloadComplete(QString /*remoteFile*/, QString localFile, QString errorMsg)
{
Q_UNUSED(remoteFile);
_loadParametersFromDownloadFile(localFile);
}
void APMAirframeComponentController::_paramFileDownloadError(QString errorMsg)
{
qgcApp()->showAppMessage(tr("Param file download failed: %1").arg(errorMsg));
qgcApp()->restoreOverrideCursor();
if (errorMsg.isEmpty()) {
_loadParametersFromDownloadFile(localFile);
} else {
qgcApp()->showAppMessage(tr("Param file download failed: %1").arg(errorMsg));
qgcApp()->restoreOverrideCursor();
}
}
APMFrameClass::APMFrameClass(const QString& name, bool copter, int frameClass, Fact* frameTypeFact, QObject* parent)
......
......@@ -35,10 +35,8 @@ public:
Q_INVOKABLE void loadParameters(const QString& paramFile);
private slots:
void _githubJsonDownloadFinished(QString remoteFile, QString localFile);
void _githubJsonDownloadError(QString errorMsg);
void _paramFileDownloadFinished(QString remoteFile, QString localFile);
void _paramFileDownloadError(QString errorMsg);
void _githubJsonDownloadComplete(QString remoteFile, QString localFile, QString errorMsg);
void _paramFileDownloadComplete(QString remoteFile, QString localFile, QString errorMsg);
private:
void _fillFrameClasses(void);
......
......@@ -831,20 +831,16 @@ void FirmwarePlugin::checkIfIsLatestStable(Vehicle* vehicle)
QGCFileDownload* downloader = new QGCFileDownload(this);
connect(
downloader,
&QGCFileDownload::downloadFinished,
&QGCFileDownload::downloadComplete,
this,
[vehicle, this](QString remoteFile, QString localFile) {
_versionFileDownloadFinished(remoteFile, localFile, vehicle);
[vehicle, this](QString remoteFile, QString localFile, QString errorMsg) {
if (errorMsg.isEmpty()) {
_versionFileDownloadFinished(remoteFile, localFile, vehicle);
} else {
qCDebug(FirmwarePluginLog) << "Failed to download the latest fw version file. Error: " << errorMsg;
}
sender()->deleteLater();
});
connect(
downloader,
&QGCFileDownload::error,
this,
[=](QString errorMsg) {
qCDebug(FirmwarePluginLog) << "Failed to download the latest fw version file. Error: " << errorMsg;
downloader->deleteLater();
});
downloader->download(versionFile);
}
......
......@@ -866,48 +866,46 @@ void QGCApplication::_checkForNewVersion()
if (_parseVersionText(applicationVersion(), _majorVersion, _minorVersion, _buildVersion)) {
QString versionCheckFile = toolbox()->corePlugin()->stableVersionCheckFileUrl();
if (!versionCheckFile.isEmpty()) {
_currentVersionDownload = new QGCFileDownload(this);
connect(_currentVersionDownload, &QGCFileDownload::downloadFinished, this, &QGCApplication::_currentVersionDownloadFinished);
connect(_currentVersionDownload, &QGCFileDownload::error, this, &QGCApplication::_currentVersionDownloadError);
_currentVersionDownload->download(versionCheckFile);
QGCFileDownload* download = new QGCFileDownload(this);
connect(download, &QGCFileDownload::downloadComplete, this, &QGCApplication::_qgcCurrentStableVersionDownloadComplete);
download->download(versionCheckFile);
}
}
}
#endif
}
void QGCApplication::_currentVersionDownloadFinished(QString /*remoteFile*/, QString localFile)
void QGCApplication::_qgcCurrentStableVersionDownloadComplete(QString /*remoteFile*/, QString localFile, QString errorMsg)
{
#ifdef __mobile__
Q_UNUSED(localFile);
Q_UNUSED(localFile)
Q_UNUSED(errorMsg)
#else
QFile versionFile(localFile);
if (versionFile.open(QIODevice::ReadOnly)) {
QTextStream textStream(&versionFile);
QString version = textStream.readLine();
qDebug() << version;
int majorVersion, minorVersion, buildVersion;
if (_parseVersionText(version, majorVersion, minorVersion, buildVersion)) {
if (_majorVersion < majorVersion ||
(_majorVersion == majorVersion && _minorVersion < minorVersion) ||
(_majorVersion == majorVersion && _minorVersion == minorVersion && _buildVersion < buildVersion)) {
//-- TODO
///QGCMessageBox::information(tr("New Version Available"), tr("There is a newer version of %1 available. You can download it from %2.").arg(applicationName()).arg(toolbox()->corePlugin()->stableDownloadLocation()));
if (errorMsg.isEmpty()) {
QFile versionFile(localFile);
if (versionFile.open(QIODevice::ReadOnly)) {
QTextStream textStream(&versionFile);
QString version = textStream.readLine();
qDebug() << version;
int majorVersion, minorVersion, buildVersion;
if (_parseVersionText(version, majorVersion, minorVersion, buildVersion)) {
if (_majorVersion < majorVersion ||
(_majorVersion == majorVersion && _minorVersion < minorVersion) ||
(_majorVersion == majorVersion && _minorVersion == minorVersion && _buildVersion < buildVersion)) {
showAppMessage(tr("There is a newer version of %1 available. You can download it from %2.").arg(applicationName()).arg(toolbox()->corePlugin()->stableDownloadLocation()), tr("New Version Available"));
}
}
}
} else {
qDebug() << "Download QGC stable version failed" << errorMsg;
}
_currentVersionDownload->deleteLater();
sender()->deleteLater();
#endif
}
void QGCApplication::_currentVersionDownloadError(QString /*errorMsg*/)
{
_currentVersionDownload->deleteLater();
}
bool QGCApplication::_parseVersionText(const QString& versionString, int& majorVersion, int& minorVersion, int& buildVersion)
{
QRegularExpression regExp("v(\\d+)\\.(\\d+)\\.(\\d+)");
......
......@@ -41,7 +41,6 @@
class QQmlApplicationEngine;
class QGCSingleton;
class QGCToolbox;
class QGCFileDownload;
/**
* @brief The main application and management class.
......@@ -166,15 +165,14 @@ public:
bool _checkTelemetrySavePath(bool useMessageBox);
private slots:
void _missingParamsDisplay (void);
void _currentVersionDownloadFinished(QString remoteFile, QString localFile);
void _currentVersionDownloadError (QString errorMsg);
bool _parseVersionText (const QString& versionString, int& majorVersion, int& minorVersion, int& buildVersion);
void _onGPSConnect (void);
void _onGPSDisconnect (void);
void _gpsSurveyInStatus (float duration, float accuracyMM, double latitude, double longitude, float altitude, bool valid, bool active);
void _gpsNumSatellites (int numSatellites);
void _showDelayedAppMessages (void);
void _missingParamsDisplay (void);
void _qgcCurrentStableVersionDownloadComplete (QString remoteFile, QString localFile, QString errorMsg);
bool _parseVersionText (const QString& versionString, int& majorVersion, int& minorVersion, int& buildVersion);
void _onGPSConnect (void);
void _onGPSDisconnect (void);
void _gpsSurveyInStatus (float duration, float accuracyMM, double latitude, double longitude, float altitude, bool valid, bool active);
void _gpsNumSatellites (int numSatellites);
void _showDelayedAppMessages (void);
private:
QObject* _rootQmlObject ();
......@@ -194,7 +192,6 @@ private:
int _majorVersion = 0;
int _minorVersion = 0;
int _buildVersion = 0;
QGCFileDownload* _currentVersionDownload = nullptr;
GPSRTKFactGroup* _gpsRtkFactGroup = nullptr;
QGCToolbox* _toolbox = nullptr;
QQuickItem* _mainRootWindow = nullptr;
......
......@@ -31,29 +31,6 @@ bool QGCFileDownload::download(const QString& remoteFile, bool redirect)
return false;
}
// Split out filename from path
QString remoteFileName = QFileInfo(remoteFile).fileName();
if (remoteFileName.isEmpty()) {
qWarning() << "Unabled to parse filename from downloadFile" << remoteFile;
return false;
}
// Strip out parameters from remote filename
int parameterIndex = remoteFileName.indexOf("?");
if (parameterIndex != -1) {
remoteFileName = remoteFileName.left(parameterIndex);
}
// Determine location to download file to
QString localFile = QStandardPaths::writableLocation(QStandardPaths::TempLocation);
if (localFile.isEmpty()) {
localFile = QStandardPaths::writableLocation(QStandardPaths::DownloadLocation);
if (localFile.isEmpty()) {
qDebug() << "Unabled to find writable download location. Tried downloads and temp directory.";
return false;
}
}
localFile += "/" + remoteFileName;
QUrl remoteUrl;
if (remoteFile.startsWith("http:") || remoteFile.startsWith("https:")) {
......@@ -72,9 +49,6 @@ bool QGCFileDownload::download(const QString& remoteFile, bool redirect)
tProxy.setType(QNetworkProxy::DefaultProxy);
setProxy(tProxy);
// 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";
......@@ -84,8 +58,7 @@ bool QGCFileDownload::download(const QString& remoteFile, bool redirect)
connect(networkReply, &QNetworkReply::downloadProgress, this, &QGCFileDownload::downloadProgress);
connect(networkReply, &QNetworkReply::finished, this, &QGCFileDownload::_downloadFinished);
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
connect(networkReply, static_cast<void (QNetworkReply::*)(QNetworkReply::NetworkError)>(&QNetworkReply::error),
this, &QGCFileDownload::_downloadError);
connect(networkReply, static_cast<void (QNetworkReply::*)(QNetworkReply::NetworkError)>(&QNetworkReply::error), this, &QGCFileDownload::_downloadError);
#else
connect(networkReply, &QNetworkReply::errorOccurred, this, &QGCFileDownload::_downloadError);
#endif
......@@ -95,10 +68,10 @@ bool QGCFileDownload::download(const QString& remoteFile, bool redirect)
void QGCFileDownload::_downloadFinished(void)
{
QNetworkReply* reply = qobject_cast<QNetworkReply*>(QObject::sender());
// 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) {
if (reply->error() != QNetworkReply::NoError) {
reply->deleteLater();
return;
}
......@@ -112,25 +85,46 @@ void QGCFileDownload::_downloadFinished(void)
return;
}
// Download file location is in user attribute
QString downloadFilename = reply->request().attribute(QNetworkRequest::User).toString();
// Split out filename from path
QString remoteFileName = QFileInfo(reply->url().toString()).fileName();
if (remoteFileName.isEmpty()) {
qWarning() << "Unabled to parse filename from remote url" << reply->url().toString();
remoteFileName = "DownloadedFile";
}
// Strip out http parameters from remote filename
int parameterIndex = remoteFileName.indexOf("?");
if (parameterIndex != -1) {
remoteFileName = remoteFileName.left(parameterIndex);
}
// Determine location to download file to
QString downloadFilename = QStandardPaths::writableLocation(QStandardPaths::TempLocation);
if (downloadFilename.isEmpty()) {
downloadFilename = QStandardPaths::writableLocation(QStandardPaths::DownloadLocation);
if (downloadFilename.isEmpty()) {
emit downloadComplete(_originalRemoteFile, QString(), tr("Unabled to find writable download location. Tried downloads and temp directory."));
return;
}
}
downloadFilename += "/" + remoteFileName;
if (!downloadFilename.isEmpty()) {
// Store downloaded file in download location
QFile file(downloadFilename);
if (!file.open(QIODevice::WriteOnly)) {
emit error(tr("Could not save downloaded file to %1. Error: %2").arg(downloadFilename).arg(file.errorString()));
if (!file.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
emit downloadComplete(_originalRemoteFile, downloadFilename, tr("Could not save downloaded file to %1. Error: %2").arg(downloadFilename).arg(file.errorString()));
return;
}
file.write(reply->readAll());
file.close();
emit downloadFinished(_originalRemoteFile, downloadFilename);
emit downloadComplete(_originalRemoteFile, downloadFilename, QString());
} else {
QString errorMsg = "Internal error";
qWarning() << errorMsg;
emit error(errorMsg);
emit downloadComplete(_originalRemoteFile, downloadFilename, errorMsg);
}
reply->deleteLater();
......@@ -151,5 +145,5 @@ void QGCFileDownload::_downloadError(QNetworkReply::NetworkError code)
errorMsg = tr("Error during download. Error: %1").arg(code);
}
emit error(errorMsg);
emit downloadComplete(_originalRemoteFile, QString(), errorMsg);
}
......@@ -7,9 +7,7 @@
*
****************************************************************************/
#ifndef QGCFileDownload_H
#define QGCFileDownload_H
#pragma once
#include <QNetworkReply>
......@@ -21,15 +19,14 @@ public:
QGCFileDownload(QObject* parent = nullptr);
/// 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
/// @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 redirect = false);
signals:
void downloadProgress(qint64 curr, qint64 total);
void downloadFinished(QString remoteFile, QString localFile);
void error(QString errorMsg);
void downloadComplete(QString remoteFile, QString localFile, QString errorMsg);
private:
void _downloadFinished(void);
......@@ -37,5 +34,3 @@ private:
QString _originalRemoteFile;
};
#endif
......@@ -14,6 +14,7 @@
#include "JsonHelper.h"
#include "CompInfoVersion.h"
#include "CompInfoParam.h"
#include "QGCFileDownload.h"
#include <QStandardPaths>
#include <QJsonDocument>
......@@ -208,7 +209,7 @@ QString RequestMetaDataTypeStateMachine::_downloadCompleteJsonWorker(const QStri
return outputFileName;
}
void RequestMetaDataTypeStateMachine::_downloadCompleteMetaDataJson(const QString& fileName, const QString& errorMsg)
void RequestMetaDataTypeStateMachine::_ftpDownloadCompleteMetaDataJson(const QString& fileName, const QString& errorMsg)
{
qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_downloadCompleteMetaDataJson fileName:errorMsg" << fileName << errorMsg;
......@@ -219,7 +220,7 @@ void RequestMetaDataTypeStateMachine::_downloadCompleteMetaDataJson(const QStrin
advance();
}
void RequestMetaDataTypeStateMachine::_downloadCompleteTranslationJson(const QString& fileName, const QString& errorMsg)
void RequestMetaDataTypeStateMachine::_ftpDownloadCompleteTranslationJson(const QString& fileName, const QString& errorMsg)
{
qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_downloadCompleteTranslationJson fileName:errorMsg" << fileName << errorMsg;
......@@ -233,6 +234,31 @@ void RequestMetaDataTypeStateMachine::_downloadCompleteTranslationJson(const QSt
advance();
}
void RequestMetaDataTypeStateMachine::_httpDownloadCompleteMetaDataJson(QString remoteFile, QString localFile, QString errorMsg)
{
qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_httpDownloadCompleteMetaDataJson remoteFile:localFile:errorMsg" << remoteFile << localFile << errorMsg;
if (errorMsg.isEmpty()) {
_jsonMetadataFileName = _downloadCompleteJsonWorker(localFile, "metadata.json");
}
advance();
}
void RequestMetaDataTypeStateMachine::_httpDownloadCompleteTranslationJson(QString remoteFile, QString localFile, QString errorMsg)
{
qCDebug(ComponentInformationManagerLog) << "RequestMetaDataTypeStateMachine::_httpDownloadCompleteTranslationJson remoteFile:localFile:errorMsg" << remoteFile << localFile << errorMsg;
QString jsonTranslationFileName;
if (errorMsg.isEmpty()) {
jsonTranslationFileName = _downloadCompleteJsonWorker(localFile, "translation.json");
}
_compInfo->setJson(_jsonMetadataFileName, jsonTranslationFileName);
advance();
}
void RequestMetaDataTypeStateMachine::_stateRequestMetaDataJson(StateMachine* stateMachine)
{
RequestMetaDataTypeStateMachine* requestMachine = static_cast<RequestMetaDataTypeStateMachine*>(stateMachine);
......@@ -242,11 +268,12 @@ void RequestMetaDataTypeStateMachine::_stateRequestMetaDataJson(StateMachine* st
if (compInfo->available) {
qCDebug(ComponentInformationManagerLog) << "Downloading metadata json" << compInfo->uriMetaData;
if (_uriIsFTP(compInfo->uriMetaData)) {
connect(ftpManager, &FTPManager::downloadComplete, requestMachine, &RequestMetaDataTypeStateMachine::_downloadCompleteMetaDataJson);
connect(ftpManager, &FTPManager::downloadComplete, requestMachine, &RequestMetaDataTypeStateMachine::_ftpDownloadCompleteMetaDataJson);
ftpManager->download(compInfo->uriMetaData, QStandardPaths::writableLocation(QStandardPaths::TempLocation));
} else {
// FIXME: NYI
qCDebug(ComponentInformationManagerLog) << "Skipping metadata json download. http download NYI";
QGCFileDownload* download = new QGCFileDownload(requestMachine);
connect(download, &QGCFileDownload::downloadComplete, requestMachine, &RequestMetaDataTypeStateMachine::_httpDownloadCompleteMetaDataJson);
download->download(compInfo->uriMetaData);
}
} else {
qCDebug(ComponentInformationManagerLog) << "Skipping metadata json download. Component information not available";
......@@ -267,11 +294,12 @@ void RequestMetaDataTypeStateMachine::_stateRequestTranslationJson(StateMachine*
} else {
qCDebug(ComponentInformationManagerLog) << "Downloading translation json" << compInfo->uriTranslation;
if (_uriIsFTP(compInfo->uriTranslation)) {
connect(ftpManager, &FTPManager::downloadComplete, requestMachine, &RequestMetaDataTypeStateMachine::_downloadCompleteTranslationJson);
connect(ftpManager, &FTPManager::downloadComplete, requestMachine, &RequestMetaDataTypeStateMachine::_ftpDownloadCompleteTranslationJson);
ftpManager->download(compInfo->uriTranslation, QStandardPaths::writableLocation(QStandardPaths::TempLocation));
} else {
// FIXME: NYI
qCDebug(ComponentInformationManagerLog) << "Skipping translation json download. http download NYI";
QGCFileDownload* download = new QGCFileDownload(requestMachine);
connect(download, &QGCFileDownload::downloadComplete, requestMachine, &RequestMetaDataTypeStateMachine::_httpDownloadCompleteTranslationJson);
download->download(compInfo->uriTranslation);
}
}
} else {
......
......@@ -38,9 +38,11 @@ public:
void statesCompleted (void) const final;
private slots:
void _downloadCompleteMetaDataJson (const QString& file, const QString& errorMsg);
void _downloadCompleteTranslationJson(const QString& file, const QString& errorMsg);
QString _downloadCompleteJsonWorker (const QString& jsonFileName, const QString& inflatedFileName);
void _ftpDownloadCompleteMetaDataJson (const QString& file, const QString& errorMsg);
void _ftpDownloadCompleteTranslationJson (const QString& file, const QString& errorMsg);
void _httpDownloadCompleteMetaDataJson (QString remoteFile, QString localFile, QString errorMsg);
void _httpDownloadCompleteTranslationJson(QString remoteFile, QString localFile, QString errorMsg);
QString _downloadCompleteJsonWorker (const QString& jsonFileName, const QString& inflatedFileName);
private:
static void _stateRequestCompInfo (StateMachine* stateMachine);
......
......@@ -169,30 +169,27 @@ signals:
void downloadingFirmwareListChanged (bool downloadingFirmwareList);
private slots:
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, QString boardName);
void _noBoardFound(void);
void _boardGone();
void _foundBoardInfo(int bootloaderVersion, int boardID, int flashSize);
void _error(const QString& errorString);
void _status(const QString& statusString);
void _bootloaderSyncFailed(void);
void _flashComplete(void);
void _updateProgress(int curr, int total);
void _eraseStarted(void);
void _eraseComplete(void);
void _eraseProgressTick(void);
void _px4ReleasesGithubDownloadFinished(QString remoteFile, QString localFile);
void _px4ReleasesGithubDownloadError(QString errorMsg);
void _ardupilotManifestDownloadFinished(QString remoteFile, QString localFile);
void _ardupilotManifestDownloadError(QString errorMsg);
void _buildAPMFirmwareNames(void);
void _firmwareDownloadProgress (qint64 curr, qint64 total);
void _firmwareDownloadComplete (QString remoteFile, QString localFile, QString errorMsg);
void _foundBoard (bool firstAttempt, const QSerialPortInfo& portInfo, int boardType, QString boardName);
void _noBoardFound (void);
void _boardGone (void);
void _foundBoardInfo (int bootloaderVersion, int boardID, int flashSize);
void _error (const QString& errorString);
void _status (const QString& statusString);
void _bootloaderSyncFailed (void);
void _flashComplete (void);
void _updateProgress (int curr, int total);
void _eraseStarted (void);
void _eraseComplete (void);
void _eraseProgressTick (void);
void _px4ReleasesGithubDownloadComplete (QString remoteFile, QString localFile, QString errorMsg);
void _ardupilotManifestDownloadComplete (QString remoteFile, QString localFile, QString errorMsg);
void _buildAPMFirmwareNames (void);
private:
QHash<FirmwareIdentifier, QString>* _firmwareHashForBoardId(int boardId);
void _getFirmwareFile(FirmwareIdentifier firmwareId);
void _getFirmwareFile (FirmwareIdentifier firmwareId);
void _initFirmwareHash (void);
void _downloadFirmware (void);
void _appendStatusLog (const QString& text, bool critical = false);
......
......@@ -1529,7 +1529,11 @@ bool MockLink::_handleRequestMessage(const mavlink_command_long_t& request, bool
void MockLink::_sendVersionMetaData(void)
{
mavlink_message_t responseMsg;
#if 1
char metaDataURI[MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_METADATA_URI_LEN] = "mavlinkftp://version.json.gz";
#else
char metaDataURI[MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_METADATA_URI_LEN] = "https://bit.ly/31nm0fs";
#endif
char translationURI[MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_TRANSLATION_URI_LEN] = "";
mavlink_msg_component_information_pack_chan(_vehicleSystemId,
......@@ -1548,7 +1552,11 @@ void MockLink::_sendVersionMetaData(void)
void MockLink::_sendParameterMetaData(void)
{
mavlink_message_t responseMsg;
#if 1
char metaDataURI[MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_METADATA_URI_LEN] = "mavlinkftp://parameter.json";
#else
char metaDataURI[MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_METADATA_URI_LEN] = "https://bit.ly/2ZKRIRE";
#endif
char translationURI[MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_TRANSLATION_URI_LEN] = "";
mavlink_msg_component_information_pack_chan(_vehicleSystemId,
......
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