Commit 443b49c3 authored by Willian Galvani's avatar Willian Galvani

FirmwarePlugin: Issue a warning upon connecting if the firmware in use is not...

FirmwarePlugin: Issue a warning upon connecting if the firmware in use is not using a stable release
parent 04d5b254
......@@ -16,6 +16,7 @@
#include "APMSensorsComponentController.h"
#include "MissionManager.h"
#include "ParameterManager.h"
#include "QGCFileDownload.h"
#include <QTcpSocket>
......@@ -1004,3 +1005,25 @@ void APMFirmwarePlugin::startMission(Vehicle* vehicle)
vehicle->sendMavCommand(vehicle->defaultComponentId(), MAV_CMD_MISSION_START, true /*show error */);
}
}
QString APMFirmwarePlugin::_getLatestVersionFileUrl(Vehicle* vehicle)
{
const static QString baseUrl("http://firmware.ardupilot.org/%1/stable/PX4/git-version.txt");
if (vehicle->fixedWing()) {
return baseUrl.arg("Plane");
}
if (vehicle->vtol()) {
return baseUrl.arg("Plane");
}
if (vehicle->rover()) {
return baseUrl.arg("Rover");
}
if (vehicle->sub()) {
return baseUrl.arg("Sub");
}
return baseUrl.arg("Copter");
}
QString APMFirmwarePlugin::_versionRegex() {
return QStringLiteral(" V([0-9,\\.]*)$");
}
......@@ -127,6 +127,8 @@ private:
void _handleOutgoingParamSet(Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message);
void _soloVideoHandshake(Vehicle* vehicle, bool originalSoloFirmware);
bool _guidedModeTakeoff(Vehicle* vehicle, double altitudeRel);
QString _getLatestVersionFileUrl(Vehicle* vehicle) override;
QString _versionRegex() override;
// Any instance data here must be global to all vehicles
// Vehicle specific data should go into APMFirmwarePluginInstanceData
......
......@@ -13,7 +13,9 @@
#include "CameraMetaData.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include "QGCFileDownload.h"
#include <QRegularExpression>
#include <QDebug>
QGC_LOGGING_CATEGORY(FirmwarePluginLog, "FirmwarePluginLog")
......@@ -665,3 +667,76 @@ uint32_t FirmwarePlugin::highLatencyCustomModeTo32Bits(uint16_t hlCustomMode)
return hlCustomMode;
}
void FirmwarePlugin::checkIfIsLatestStable(Vehicle* vehicle)
{
// This is required as mocklink uses a hardcoded firmware version
if (qgcApp()->runningUnitTests()) {
qCDebug(FirmwarePluginLog) << "Skipping version check";
return;
}
QString versionFile = _getLatestVersionFileUrl(vehicle);
qCDebug(FirmwarePluginLog) << "Downloading" << versionFile;
QGCFileDownload* downloader = new QGCFileDownload(this);
connect(
downloader,
&QGCFileDownload::downloadFinished,
this,
[vehicle, this](QString remoteFile, QString localFile) {
_versionFileDownloadFinished(remoteFile, localFile, vehicle);
sender()->deleteLater();
});
downloader->download(versionFile);
}
void FirmwarePlugin::_versionFileDownloadFinished(QString& remoteFile, QString& localFile, Vehicle* vehicle)
{
qCDebug(FirmwarePluginLog) << "Download complete" << remoteFile << localFile;
// Now read the version file and pull out the version string
QFile versionFile(localFile);
if (!versionFile.open(QIODevice::ReadOnly | QIODevice::Text)) {
qCWarning(FirmwarePluginLog) << "Error opening downloaded version file.";
return;
}
QTextStream stream(&versionFile);
QString versionFileContents = stream.readAll();
QString version;
QRegularExpressionMatch match = QRegularExpression(_versionRegex()).match(versionFileContents);
qCDebug(FirmwarePluginLog) << "Looking for version number...";
if (match.hasMatch()) {
version = match.captured(1);
} else {
qCWarning(FirmwarePluginLog) << "Unable to parse version info from file" << remoteFile;
return;
}
qCDebug(FirmwarePluginLog) << "Latest stable version = " << version;
QStringList versionNumbers = version.split(".");
if(versionNumbers.size() != 3) {
qCWarning(FirmwarePluginLog) << "Error parsing version number: wrong format";
return;
}
int stableMajor = versionNumbers[0].toInt();
int stableMinor = versionNumbers[1].toInt();
int stablePatch = versionNumbers[2].toInt();
int currMajor = vehicle->firmwareMajorVersion();
int currMinor = vehicle->firmwareMinorVersion();
int currPatch = vehicle->firmwarePatchVersion();
int currType = vehicle->firmwareVersionType();
if (currMajor < stableMajor
|| (currMajor == stableMajor && currMinor < stableMinor)
|| (currMajor == stableMajor && currMinor == stableMinor && currPatch < stablePatch)
|| (currMajor == stableMajor && currMinor == stableMinor && currPatch == stablePatch && currType != FIRMWARE_VERSION_TYPE_OFFICIAL)
)
{
const static QString currentVersion = QString("%1.%2.%3").arg(vehicle->firmwareMajorVersion())
.arg(vehicle->firmwareMinorVersion())
.arg(vehicle->firmwarePatchVersion());
const static QString message = tr("Vehicle is not running latest stable firmware! Running %2-%1, latest stable is %3.");
qgcApp()->showMessage(message.arg(vehicle->firmwareVersionTypeString(), currentVersion, version));
}
}
......@@ -306,6 +306,9 @@ public:
/// Convert from HIGH_LATENCY2.custom_mode value to correct 32 bit value.
virtual uint32_t highLatencyCustomModeTo32Bits(uint16_t hlCustomMode);
/// Used to check if running firmware is latest stable version.
virtual void checkIfIsLatestStable(Vehicle* vehicle);
// FIXME: Hack workaround for non pluginize FollowMe support
static const QString px4FollowMeFlightMode;
......@@ -321,6 +324,15 @@ protected:
// @return: true - vehicle in specified flight mode, false - flight mode change failed
bool _setFlightModeAndValidate(Vehicle* vehicle, const QString& flightMode);
// returns url with latest firmware release information.
virtual QString _getLatestVersionFileUrl(Vehicle* vehicle) { Q_UNUSED(vehicle); return QString(); }
// Callback to process file with latest release information
virtual void _versionFileDownloadFinished(QString& remoteFile, QString& localFile, Vehicle* vehicle);
// Returns regex QString to extract version information from text
virtual QString _versionRegex() { return QString(); }
private:
QVariantList _toolBarIndicatorList;
static QVariantList _cameraList; ///< Standard QGC camera list
......
......@@ -22,6 +22,7 @@
#include "PowerComponentController.h"
#include "RadioComponentController.h"
#include "QGCCameraManager.h"
#include "QGCFileDownload.h"
#include <QDebug>
......@@ -597,3 +598,12 @@ uint32_t PX4FirmwarePlugin::highLatencyCustomModeTo32Bits(uint16_t hlCustomMode)
return px4_cm.data;
}
QString PX4FirmwarePlugin::_getLatestVersionFileUrl(Vehicle* vehicle){
Q_UNUSED(vehicle);
return QStringLiteral("https://api.github.com/repos/PX4/Firmware/releases");
}
QString PX4FirmwarePlugin::_versionRegex() {
return QStringLiteral("v([0-9,\\.]*) Stable");
}
......@@ -111,6 +111,8 @@ private slots:
private:
void _handleAutopilotVersion(Vehicle* vehicle, mavlink_message_t* message);
QString _getLatestVersionFileUrl(Vehicle* vehicle) override;
QString _versionRegex() override;
// Any instance data here must be global to all vehicles
// Vehicle specific data should go into PX4FirmwarePluginInstanceData
......
......@@ -1239,6 +1239,7 @@ void Vehicle::_handleAutopilotVersion(LinkInterface *link, mavlink_message_t& me
// APM Firmware stores the first 8 characters of the git hash as an ASCII character string
_gitHash = QString::fromUtf8((char*)autopilotVersion.flight_custom_version, 8);
}
_firmwarePlugin->checkIfIsLatestStable(this);
emit gitHashChanged(_gitHash);
_setCapabilities(autopilotVersion.capabilities);
......
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