From 158fd4e57c017a2e100a7c436121fc156fc97ae5 Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Mon, 8 Oct 2018 15:31:15 -0300 Subject: [PATCH] FirmwarePlugin.cc: update to use versionCompare() --- src/FirmwarePlugin/APM/APMFirmwarePlugin.cc | 75 +++++++-------------- src/FirmwarePlugin/FirmwarePlugin.cc | 19 +----- 2 files changed, 26 insertions(+), 68 deletions(-) diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index bfdecc6e0..9a66b8fd3 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -761,9 +761,6 @@ void APMFirmwarePlugin::_artooSocketError(QAbstractSocket::SocketError socketErr QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) { - int majorVersion = vehicle->firmwareMajorVersion(); - int minorVersion = vehicle->firmwareMinorVersion(); - switch (vehicle->vehicleType()) { case MAV_TYPE_QUADROTOR: case MAV_TYPE_HEXAROTOR: @@ -771,25 +768,17 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) case MAV_TYPE_TRICOPTER: case MAV_TYPE_COAXIAL: case MAV_TYPE_HELICOPTER: - if (majorVersion < 3) { + if (vehicle->versionCompare(3,4,0) < 0) { return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml"); - } else if (majorVersion == 3) { - switch (minorVersion) { - case 0: - case 1: - case 2: - case 3: - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml"); - case 4: - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.4.xml"); - case 5: - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"); - case 6: - default: - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml"); - } } - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"); + if (vehicle->versionCompare(3,5,0) < 0) { + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.4.xml"); + } + if (vehicle->versionCompare(3,6,0) < 0) { + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"); + } + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml"); + case MAV_TYPE_VTOL_DUOROTOR: case MAV_TYPE_VTOL_QUADROTOR: case MAV_TYPE_VTOL_TILTROTOR: @@ -798,45 +787,27 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) case MAV_TYPE_VTOL_RESERVED4: case MAV_TYPE_VTOL_RESERVED5: case MAV_TYPE_FIXED_WING: - if (majorVersion < 3) { + if (vehicle->versionCompare(3,5,0) < 0) { return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml"); - } else if (majorVersion == 3) { - switch (minorVersion) { - case 0: - case 1: - case 2: - case 3: - case 4: - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml"); - case 5: - case 6: - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.5.xml"); - case 7: - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.7.xml"); - case 8: - default: - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml"); - } + } + if (vehicle->versionCompare(3,7,0) < 0) { + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.5.xml"); + } + if (vehicle->versionCompare(3,8,0) < 0) { + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.7.xml"); } return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml"); + case MAV_TYPE_GROUND_ROVER: case MAV_TYPE_SURFACE_BOAT: - if (majorVersion < 3) { + if (vehicle->versionCompare(3,2,0) < 0) { return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml"); - } else if (majorVersion == 3) { - switch (minorVersion) { - case 0: - case 1: - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml"); - case 2: - case 3: - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml"); - case 4: - default: - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.4.xml"); - } } - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml"); + if (vehicle->versionCompare(3,4,0) < 0) { + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml"); + } + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.4.xml"); + case MAV_TYPE_SUBMARINE: if (vehicle->firmwareMajorVersion() < 3 || (vehicle->firmwareMajorVersion() == 3 && vehicle->firmwareMinorVersion() <= 4)) { return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml"); diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc index f74897bfd..52086f1a1 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.cc +++ b/src/FirmwarePlugin/FirmwarePlugin.cc @@ -713,25 +713,12 @@ void FirmwarePlugin::_versionFileDownloadFinished(QString& remoteFile, QString& } 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) - ) + // Check if lower version than stable or same version but different type + if (vehicle->versionCompare(version) < 0 + || (vehicle->versionCompare(version) == 0 && currType != FIRMWARE_VERSION_TYPE_OFFICIAL)) { const static QString currentVersion = QString("%1.%2.%3").arg(vehicle->firmwareMajorVersion()) .arg(vehicle->firmwareMinorVersion()) -- 2.22.0