Skip to content

Commit

Permalink
Support future APMParameterFactMetaData versions
Browse files Browse the repository at this point in the history
  • Loading branch information
HTRamsey authored and DonLakeFlyer committed Mar 13, 2024
1 parent ec30ec3 commit 2f60658
Show file tree
Hide file tree
Showing 7 changed files with 40 additions and 84 deletions.
102 changes: 29 additions & 73 deletions src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -689,93 +689,49 @@ void APMFirmwarePlugin::_artooSocketError(QAbstractSocket::SocketError socketErr
qgcApp()->showAppMessage(tr("Error during Solo video link setup: %1").arg(socketError));
}

QString APMFirmwarePlugin::_internalParameterMetaDataFile(Vehicle* vehicle)
QString APMFirmwarePlugin::_internalParameterMetaDataFile(const Vehicle* vehicle) const
{
switch (vehicle->vehicleType()) {
case MAV_TYPE_QUADROTOR:
case MAV_TYPE_HEXAROTOR:
case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER:
case MAV_TYPE_COAXIAL:
case MAV_TYPE_HELICOPTER:
if (vehicle->versionCompare(4, 2, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.4.2.xml");
}
if (vehicle->versionCompare(4, 1, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.4.1.xml");
}
if (vehicle->versionCompare(4, 0, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.4.0.xml");
}
if (vehicle->versionCompare(3, 7, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.7.xml");
}
if (vehicle->versionCompare(3, 6, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml");
const QGCMAVLink::VehicleClass_t vehicleClass = QGCMAVLink::vehicleClass(vehicle->vehicleType());
const int currMajor = vehicle->firmwareMajorVersion();
const int currMinor = vehicle->firmwareMinorVersion();
QString fileName = QString(":/FirmwarePlugin/APM/APMParameterFactMetaData.{Vehicle}.%1.%2.xml").arg(currMajor).arg(currMinor);

switch (vehicleClass) {
case QGCMAVLink::VehicleClassMultiRotor:
fileName.replace("{Vehicle}", "Copter");
if(QFileInfo::exists(fileName))
{
return fileName;
}
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml");

case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
case MAV_TYPE_VTOL_FIXEDROTOR:
case MAV_TYPE_VTOL_TAILSITTER:
case MAV_TYPE_VTOL_TILTWING:
case MAV_TYPE_VTOL_RESERVED5:
case MAV_TYPE_FIXED_WING:
if (vehicle->versionCompare(4, 2, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.4.2.xml");
}
if (vehicle->versionCompare(4, 1, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.4.1.xml");
}
if (vehicle->versionCompare(4, 0, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.4.0.xml");
}
if (vehicle->versionCompare(3, 10, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.10.xml");
}
if (vehicle->versionCompare(3, 9, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.9.xml");
case QGCMAVLink::VehicleClassFixedWing:
case QGCMAVLink::VehicleClassVTOL:
fileName.replace("{Vehicle}", "Plane");
if(QFileInfo::exists(fileName))
{
return fileName;
}
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml");

case MAV_TYPE_GROUND_ROVER:
case MAV_TYPE_SURFACE_BOAT:
if (vehicle->versionCompare(4, 2, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.4.2.xml");
}
if (vehicle->versionCompare(4, 1, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.4.1.xml");
}
if (vehicle->versionCompare(4, 0, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.4.0.xml");
}
if (vehicle->versionCompare(3, 6, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.6.xml");
}
if (vehicle->versionCompare(3, 5, 0) >= 0) {
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.5.xml");
case QGCMAVLink::VehicleClassRoverBoat:
fileName.replace("{Vehicle}", "Rover");
if(QFileInfo::exists(fileName))
{
return fileName;
}
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.4.xml");

case MAV_TYPE_SUBMARINE:
if (vehicle->versionCompare(4, 1, 0) >= 0) { // 4.1.x
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.4.1.xml");
}
if (vehicle->versionCompare(4, 0, 0) >= 0) { // 4.0.x
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.4.0.xml");
}
if (vehicle->versionCompare(3, 6, 0) >= 0) { // 3.6.x
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.6.xml");
}
if (vehicle->versionCompare(3, 5, 0) >= 0) { // 3.5.x
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.5.xml");
case QGCMAVLink::VehicleClassSub:
fileName.replace("{Vehicle}", "Sub");
if(QFileInfo::exists(fileName))
{
return fileName;
}
// up to 3.4.x
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml");

default:
qWarning() << Q_FUNC_INFO << "called with bad VehicleClass_t:" << vehicleClass;
return QString();
}
}
Expand Down
2 changes: 1 addition & 1 deletion src/FirmwarePlugin/APM/APMFirmwarePlugin.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ class APMFirmwarePlugin : public FirmwarePlugin
void initializeVehicle (Vehicle* vehicle) override;
bool sendHomePositionToVehicle (void) override;
QString missionCommandOverrides (QGCMAVLink::VehicleClass_t vehicleClass) const override;
QString _internalParameterMetaDataFile (Vehicle* vehicle) override;
QString _internalParameterMetaDataFile (const Vehicle* vehicle) const override;
FactMetaData* _getMetaDataForFact (QObject* parameterMetaData, const QString& name, FactMetaData::ValueType_t type, MAV_TYPE vehicleType) override;
void _getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion) override { APMParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); }
QObject* _loadParameterMetaData (const QString& metaDataFile) override;
Expand Down
4 changes: 2 additions & 2 deletions src/FirmwarePlugin/FirmwarePlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1094,7 +1094,7 @@ void FirmwarePlugin::_versionFileDownloadFinished(QString& remoteFile, QString&
}
}

int FirmwarePlugin::versionCompare(Vehicle* vehicle, int major, int minor, int patch)
int FirmwarePlugin::versionCompare(const Vehicle* vehicle, int major, int minor, int patch) const
{
int currMajor = vehicle->firmwareMajorVersion();
int currMinor = vehicle->firmwareMinorVersion();
Expand All @@ -1113,7 +1113,7 @@ int FirmwarePlugin::versionCompare(Vehicle* vehicle, int major, int minor, int p
return -1;
}

int FirmwarePlugin::versionCompare(Vehicle* vehicle, QString& compare)
int FirmwarePlugin::versionCompare(const Vehicle* vehicle, QString& compare) const
{
QStringList versionNumbers = compare.split(".");
if(versionNumbers.size() != 3) {
Expand Down
6 changes: 3 additions & 3 deletions src/FirmwarePlugin/FirmwarePlugin.h
Original file line number Diff line number Diff line change
Expand Up @@ -241,7 +241,7 @@ class FirmwarePlugin : public QObject

/// Returns the internal resource parameter meta date file.
/// Important: Only CompInfoParam code should use this method
virtual QString _internalParameterMetaDataFile(Vehicle* /*vehicle*/) { return QString(); }
virtual QString _internalParameterMetaDataFile(const Vehicle* /*vehicle*/) const { return QString(); }

/// Loads the specified parameter meta data file.
/// @return Opaque parameter meta data information which must be stored with Vehicle. Vehicle is responsible to
Expand Down Expand Up @@ -338,8 +338,8 @@ class FirmwarePlugin : public QObject

/// 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);
int versionCompare(const Vehicle* vehicle, QString& compare) const;
int versionCompare(const Vehicle* vehicle, int major, int minor, int patch) const;

/// Allows the Firmware plugin to override the facts meta data.
/// @param vehicleType - Type of current vehicle
Expand Down
2 changes: 1 addition & 1 deletion src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ class PX4FirmwarePlugin : public FirmwarePlugin
bool sendHomePositionToVehicle (void) override;
QString missionCommandOverrides (QGCMAVLink::VehicleClass_t vehicleClass) const override;
FactMetaData* _getMetaDataForFact (QObject* parameterMetaData, const QString& name, FactMetaData::ValueType_t type, MAV_TYPE vehicleType) override;
QString _internalParameterMetaDataFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QString(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"); }
QString _internalParameterMetaDataFile (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QString(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"); }
void _getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion) override;
QObject* _loadParameterMetaData (const QString& metaDataFile) final;
bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) override;
Expand Down
4 changes: 2 additions & 2 deletions src/Vehicle/Vehicle.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4024,12 +4024,12 @@ void Vehicle::_mavlinkMessageStatus(int uasId, uint64_t totalSent, uint64_t tota
}
}

int Vehicle::versionCompare(QString& compare)
int Vehicle::versionCompare(QString& compare) const
{
return _firmwarePlugin->versionCompare(this, compare);
}

int Vehicle::versionCompare(int major, int minor, int patch)
int Vehicle::versionCompare(int major, int minor, int patch) const
{
return _firmwarePlugin->versionCompare(this, major, minor, patch);
}
Expand Down
4 changes: 2 additions & 2 deletions src/Vehicle/Vehicle.h
Original file line number Diff line number Diff line change
Expand Up @@ -452,8 +452,8 @@ class Vehicle : public FactGroup

/// 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);
Q_INVOKABLE int versionCompare(QString& compare) const;
Q_INVOKABLE int versionCompare(int major, int minor, int patch) const;

/// Test motor
/// @param motor Motor number, 1-based
Expand Down

0 comments on commit 2f60658

Please sign in to comment.