Unverified Commit 9468fca3 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #6913 from Williangalvani/versionhelper

Create Helper functions to simplify version checking
parents 462186c6 73aeee55
...@@ -72,7 +72,7 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void) ...@@ -72,7 +72,7 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
} }
// No flight modes component for Sub versions 3.5 and up // No flight modes component for Sub versions 3.5 and up
if (!_vehicle->sub() || (_vehicle->firmwareMajorVersion() == 3 && _vehicle->firmwareMinorVersion() <= 4)) { if (!_vehicle->sub() || (_vehicle->versionCompare(3, 5, 0) < 0)) {
_flightModesComponent = new APMFlightModesComponent(_vehicle, this); _flightModesComponent = new APMFlightModesComponent(_vehicle, this);
_flightModesComponent->setupTriggerSignals(); _flightModesComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_flightModesComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_flightModesComponent));
...@@ -86,8 +86,7 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void) ...@@ -86,8 +86,7 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
_powerComponent->setupTriggerSignals(); _powerComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_powerComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_powerComponent));
int versionInt = _vehicle->firmwareMajorVersion() * 100 + _vehicle->firmwareMinorVersion() * 10 + _vehicle->firmwarePatchVersion(); if (_vehicle->sub() && _vehicle->versionCompare(3, 5, 3) >= 0) {
if (_vehicle->sub() && versionInt >= 353) {
_motorComponent = new APMMotorComponent(_vehicle, this); _motorComponent = new APMMotorComponent(_vehicle, this);
_motorComponent->setupTriggerSignals(); _motorComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_motorComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_motorComponent));
...@@ -116,7 +115,7 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void) ...@@ -116,7 +115,7 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
_lightsComponent->setupTriggerSignals(); _lightsComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_lightsComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_lightsComponent));
if(_vehicle->firmwareMajorVersion() > 3 || (_vehicle->firmwareMajorVersion() == 3 && _vehicle->firmwareMinorVersion() >= 5)) { if(_vehicle->versionCompare(3, 5, 0) >= 0) {
_subFrameComponent = new APMSubFrameComponent(_vehicle, this); _subFrameComponent = new APMSubFrameComponent(_vehicle, this);
_subFrameComponent->setupTriggerSignals(); _subFrameComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_subFrameComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_subFrameComponent));
......
...@@ -34,7 +34,7 @@ SetupPage { ...@@ -34,7 +34,7 @@ SetupPage {
QGCPalette { id: palette; colorGroupEnabled: true } QGCPalette { id: palette; colorGroupEnabled: true }
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _oldFW: !(_activeVehicle.firmwareMajorVersion > 3 || _activeVehicle.firmwareMinorVersion > 5 || _activeVehicle.firmwarePatchVersion >= 2) property bool _oldFW: _activeVehicle.versionCompare(3, 5, 2) < 0
property Fact _rc5Function: controller.getParameterFact(-1, "r.SERVO5_FUNCTION") property Fact _rc5Function: controller.getParameterFact(-1, "r.SERVO5_FUNCTION")
property Fact _rc6Function: controller.getParameterFact(-1, "r.SERVO6_FUNCTION") property Fact _rc6Function: controller.getParameterFact(-1, "r.SERVO6_FUNCTION")
property Fact _rc7Function: controller.getParameterFact(-1, "r.SERVO7_FUNCTION") property Fact _rc7Function: controller.getParameterFact(-1, "r.SERVO7_FUNCTION")
......
...@@ -36,7 +36,7 @@ SetupPage { ...@@ -36,7 +36,7 @@ SetupPage {
QGCPalette { id: ggcPal; colorGroupEnabled: true } QGCPalette { id: ggcPal; colorGroupEnabled: true }
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _firmware34: _activeVehicle.firmwareMajorVersion == 3 && _activeVehicle.firmwareMinorVersion == 4 property bool _firmware34: _activeVehicle.versionCompare(3, 5, 0) < 0
// Enable/Action parameters // Enable/Action parameters
property Fact _failsafeBatteryEnable: controller.getParameterFact(-1, "r.BATT_FS_LOW_ACT") property Fact _failsafeBatteryEnable: controller.getParameterFact(-1, "r.BATT_FS_LOW_ACT")
......
...@@ -13,7 +13,7 @@ FactPanel { ...@@ -13,7 +13,7 @@ FactPanel {
color: qgcPal.windowShadeDark color: qgcPal.windowShadeDark
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _firmware34: _activeVehicle.firmwareMajorVersion == 3 && _activeVehicle.firmwareMinorVersion == 4 property bool _firmware34: _activeVehicle.versionCompare(3, 5, 0) < 0
QGCPalette { id: qgcPal; colorGroupEnabled: enabled } QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
FactPanelController { id: controller; factPanel: panel } FactPanelController { id: controller; factPanel: panel }
......
...@@ -25,7 +25,7 @@ SetupPage { ...@@ -25,7 +25,7 @@ SetupPage {
pageComponent: subFramePageComponent pageComponent: subFramePageComponent
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _oldFW: !(_activeVehicle.firmwareMajorVersion > 3 || _activeVehicle.firmwareMinorVersion > 5 || _activeVehicle.firmwarePatchVersion >= 2) property bool _oldFW: _activeVehicle.versionCompare(3 ,5 ,2) < 0
APMAirframeComponentController { id: controller; factPanel: subFramePage.viewPanel } APMAirframeComponentController { id: controller; factPanel: subFramePage.viewPanel }
......
...@@ -761,9 +761,6 @@ void APMFirmwarePlugin::_artooSocketError(QAbstractSocket::SocketError socketErr ...@@ -761,9 +761,6 @@ void APMFirmwarePlugin::_artooSocketError(QAbstractSocket::SocketError socketErr
QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
{ {
int majorVersion = vehicle->firmwareMajorVersion();
int minorVersion = vehicle->firmwareMinorVersion();
switch (vehicle->vehicleType()) { switch (vehicle->vehicleType()) {
case MAV_TYPE_QUADROTOR: case MAV_TYPE_QUADROTOR:
case MAV_TYPE_HEXAROTOR: case MAV_TYPE_HEXAROTOR:
...@@ -771,25 +768,18 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) ...@@ -771,25 +768,18 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
case MAV_TYPE_TRICOPTER: case MAV_TYPE_TRICOPTER:
case MAV_TYPE_COAXIAL: case MAV_TYPE_COAXIAL:
case MAV_TYPE_HELICOPTER: case MAV_TYPE_HELICOPTER:
if (majorVersion < 3) { if (vehicle->versionCompare(3, 6, 0) >= 0) { // 3.6.0 and higher
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml");
} else if (majorVersion == 3) { }
switch (minorVersion) { if (vehicle->versionCompare(3, 5, 0) >= 0) { // 3.5.x
case 0: return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml");
case 1: }
case 2: if (vehicle->versionCompare(3, 4, 0) >= 0) { // 3.4.x
case 3: return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.4.xml");
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"); // Up to 3.3.x
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml");
case MAV_TYPE_VTOL_DUOROTOR: case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR: case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR: case MAV_TYPE_VTOL_TILTROTOR:
...@@ -798,53 +788,39 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) ...@@ -798,53 +788,39 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
case MAV_TYPE_VTOL_RESERVED4: case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5: case MAV_TYPE_VTOL_RESERVED5:
case MAV_TYPE_FIXED_WING: case MAV_TYPE_FIXED_WING:
if (majorVersion < 3) { if (vehicle->versionCompare(3, 8, 0) >= 0) { // 3.8.0 and higher
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml");
} else if (majorVersion == 3) { }
switch (minorVersion) { if (vehicle->versionCompare(3, 7, 0) >= 0) { // 3.7.x
case 0: return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.7.xml");
case 1: }
case 2: if (vehicle->versionCompare(3, 5, 0) >= 0) { // 3.5.x to 3.6.x
case 3: return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.5.xml");
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");
}
} }
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml"); // up to 3.4.x
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml");
case MAV_TYPE_GROUND_ROVER: case MAV_TYPE_GROUND_ROVER:
case MAV_TYPE_SURFACE_BOAT: case MAV_TYPE_SURFACE_BOAT:
if (majorVersion < 3) { if (vehicle->versionCompare(3, 4, 0) >= 0) { // 3.4.0 and higher
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.4.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, 2, 0) >= 0) { // 3.2.x to 3.3.x
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml");
}
// up to 3.1.x
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml");
case MAV_TYPE_SUBMARINE: case MAV_TYPE_SUBMARINE:
if (vehicle->firmwareMajorVersion() < 3 || (vehicle->firmwareMajorVersion() == 3 && vehicle->firmwareMinorVersion() <= 4)) { if (vehicle->versionCompare(3, 6, 0) >= 0) { // 3.5.x
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml");
} else if (vehicle->firmwareMinorVersion() <= 5) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.5.xml");
} else {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.6dev.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.6dev.xml");
} }
if (vehicle->versionCompare(3, 5, 0) >= 0) { // 3.5.x
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.5.xml");
}
// up to 3.4.x
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml");
default: default:
return QString(); return QString();
} }
......
...@@ -713,25 +713,12 @@ void FirmwarePlugin::_versionFileDownloadFinished(QString& remoteFile, QString& ...@@ -713,25 +713,12 @@ void FirmwarePlugin::_versionFileDownloadFinished(QString& remoteFile, QString&
} }
qCDebug(FirmwarePluginLog) << "Latest stable version = " << version; 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(); int currType = vehicle->firmwareVersionType();
if (currMajor < stableMajor // Check if lower version than stable or same version but different type
|| (currMajor == stableMajor && currMinor < stableMinor) if (vehicle->versionCompare(version) < 0
|| (currMajor == stableMajor && currMinor == stableMinor && currPatch < stablePatch) || (vehicle->versionCompare(version) == 0 && currType != FIRMWARE_VERSION_TYPE_OFFICIAL))
|| (currMajor == stableMajor && currMinor == stableMinor && currPatch == stablePatch && currType != FIRMWARE_VERSION_TYPE_OFFICIAL)
)
{ {
const static QString currentVersion = QString("%1.%2.%3").arg(vehicle->firmwareMajorVersion()) const static QString currentVersion = QString("%1.%2.%3").arg(vehicle->firmwareMajorVersion())
.arg(vehicle->firmwareMinorVersion()) .arg(vehicle->firmwareMinorVersion())
...@@ -740,3 +727,35 @@ void FirmwarePlugin::_versionFileDownloadFinished(QString& remoteFile, QString& ...@@ -740,3 +727,35 @@ void FirmwarePlugin::_versionFileDownloadFinished(QString& remoteFile, QString&
qgcApp()->showMessage(message.arg(vehicle->firmwareVersionTypeString(), currentVersion, version)); qgcApp()->showMessage(message.arg(vehicle->firmwareVersionTypeString(), currentVersion, version));
} }
} }
int FirmwarePlugin::versionCompare(Vehicle* vehicle, int major, int minor, int patch)
{
int currMajor = vehicle->firmwareMajorVersion();
int currMinor = vehicle->firmwareMinorVersion();
int currPatch = vehicle->firmwarePatchVersion();
if (currMajor == major && currMinor == minor && currPatch == patch) {
return 0;
}
if (currMajor > major
|| (currMajor == major && currMinor > minor)
|| (currMajor == major && currMinor == minor && currPatch > patch))
{
return 1;
}
return -1;
}
int FirmwarePlugin::versionCompare(Vehicle* vehicle, QString& compare)
{
QStringList versionNumbers = compare.split(".");
if(versionNumbers.size() != 3) {
qCWarning(FirmwarePluginLog) << "Error parsing version number: wrong format";
return -1;
}
int major = versionNumbers[0].toInt();
int minor = versionNumbers[1].toInt();
int patch = versionNumbers[2].toInt();
return versionCompare(vehicle, major, minor, patch);
}
...@@ -309,6 +309,11 @@ public: ...@@ -309,6 +309,11 @@ public:
/// Used to check if running firmware is latest stable version. /// Used to check if running firmware is latest stable version.
virtual void checkIfIsLatestStable(Vehicle* vehicle); virtual void checkIfIsLatestStable(Vehicle* vehicle);
/// Used to check if running current version is equal or higher than the one being compared.
/// returns 1 if current > compare, 0 if current == compare, -1 if current < compare
int versionCompare(Vehicle* vehicle, QString& compare);
int versionCompare(Vehicle* vehicle, int major, int minor, int patch);
// FIXME: Hack workaround for non pluginize FollowMe support // FIXME: Hack workaround for non pluginize FollowMe support
static const QString px4FollowMeFlightMode; static const QString px4FollowMeFlightMode;
......
...@@ -3770,6 +3770,16 @@ void Vehicle::_mavlinkMessageStatus(int uasId, uint64_t totalSent, uint64_t tota ...@@ -3770,6 +3770,16 @@ void Vehicle::_mavlinkMessageStatus(int uasId, uint64_t totalSent, uint64_t tota
} }
} }
int Vehicle::versionCompare(QString& compare)
{
return _firmwarePlugin->versionCompare(this, compare);
}
int Vehicle::versionCompare(int major, int minor, int patch)
{
return _firmwarePlugin->versionCompare(this, major, minor, patch);
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
......
...@@ -746,6 +746,11 @@ public: ...@@ -746,6 +746,11 @@ public:
Q_INVOKABLE void triggerCamera(void); Q_INVOKABLE void triggerCamera(void);
Q_INVOKABLE void sendPlan(QString planFile); Q_INVOKABLE void sendPlan(QString planFile);
/// Used to check if running current version is equal or higher than the one being compared.
// returns 1 if current > compare, 0 if current == compare, -1 if current < compare
Q_INVOKABLE int versionCompare(QString& compare);
Q_INVOKABLE int versionCompare(int major, int minor, int patch);
/// Test motor /// Test motor
/// @param motor Motor number, 1-based /// @param motor Motor number, 1-based
/// @param percent 0-no power, 100-full power /// @param percent 0-no power, 100-full power
......
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